![]() |
MercurySDK
Software development kit for Mercury digital servos
|
The class for reading multiple Dynamixel data from same address with same length at once. More...
#include <group_sync_read.h>
Public Member Functions | |
GroupSyncRead (PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length) | |
The function that Initializes instance for Sync Read. More... | |
~GroupSyncRead () | |
The function that calls clearParam function to clear the parameter list for Sync Read. More... | |
bool | addParam (uint8_t id) |
The function that adds id, start_address, data_length to the Sync Read list. More... | |
void | removeParam (uint8_t id) |
The function that removes id from the Sync Read list. More... | |
void | clearParam () |
The function that clears the Sync Read list. More... | |
int | txPacket () |
The function that transmits the Sync Read instruction packet which might be constructed by GroupSyncRead::addParam function. More... | |
int | rxPacket () |
The function that receives the packet which might be come from the Dynamixel. More... | |
int | txRxPacket () |
The function that transmits and receives the packet which might be come from the Dynamixel. More... | |
bool | isAvailable (uint8_t id, uint16_t address, uint16_t data_length) |
The function that checks whether there are available data which might be received by GroupSyncRead::rxPacket or GroupSyncRead::txRxPacket. More... | |
uint32_t | getData (uint8_t id, uint16_t address, uint16_t data_length) |
The function that gets the data which might be received by GroupSyncRead::rxPacket or GroupSyncRead::txRxPacket. More... | |
bool | getError (uint8_t id, uint8_t *error) |
The function that gets the error which might be received by GroupSyncRead::rxPacket or GroupSyncRead::txRxPacket. More... | |
![]() | |
GroupHandler (PortHandler *port, PacketHandler *ph) | |
PortHandler * | getPortHandler () |
PacketHandler * | getPacketHandler () |
Protected Member Functions | |
void | makeParam () |
Protected Attributes | |
std::map< uint8_t, uint8_t * > | error_list_ |
bool | last_result_ |
uint16_t | start_address_ |
uint16_t | data_length_ |
![]() | |
PortHandler * | port_ |
PacketHandler * | ph_ |
std::vector< uint8_t > | id_list_ |
std::map< uint8_t, uint8_t * > | data_list_ |
bool | is_param_changed_ |
uint8_t * | param_ |
The class for reading multiple Dynamixel data from same address with same length at once.
Definition at line 36 of file group_sync_read.h.
GroupSyncRead::GroupSyncRead | ( | PortHandler * | port, |
PacketHandler * | ph, | ||
uint16_t | start_address, | ||
uint16_t | data_length | ||
) |
The function that Initializes instance for Sync Read.
port | PortHandler instance |
ph | PacketHandler instance |
start_address | Address of the data for read |
data_length | Length of the data for read |
Definition at line 34 of file group_sync_read.cpp.
|
inline |
The function that calls clearParam function to clear the parameter list for Sync Read.
Definition at line 61 of file group_sync_read.h.
bool GroupSyncRead::addParam | ( | uint8_t | id | ) |
The function that adds id, start_address, data_length to the Sync Read list.
id | Dynamixel ID |
Definition at line 59 of file group_sync_read.cpp.
void GroupSyncRead::clearParam | ( | ) |
The function that clears the Sync Read list.
Definition at line 91 of file group_sync_read.cpp.
uint32_t GroupSyncRead::getData | ( | uint8_t | id, |
uint16_t | address, | ||
uint16_t | data_length | ||
) |
The function that gets the data which might be received by GroupSyncRead::rxPacket or GroupSyncRead::txRxPacket.
id | Dynamixel ID |
address | Address of the data for read @data_length Length of the data for read |
Definition at line 174 of file group_sync_read.cpp.
bool GroupSyncRead::getError | ( | uint8_t | id, |
uint8_t * | error | ||
) |
The function that gets the error which might be received by GroupSyncRead::rxPacket or GroupSyncRead::txRxPacket.
id | Dynamixel ID @error error of Dynamixel |
Definition at line 196 of file group_sync_read.cpp.
bool GroupSyncRead::isAvailable | ( | uint8_t | id, |
uint16_t | address, | ||
uint16_t | data_length | ||
) |
The function that checks whether there are available data which might be received by GroupSyncRead::rxPacket or GroupSyncRead::txRxPacket.
id | Dynamixel ID |
address | Address of the data for read |
data_length | Length of the data for read |
Definition at line 163 of file group_sync_read.cpp.
|
protected |
Definition at line 43 of file group_sync_read.cpp.
void GroupSyncRead::removeParam | ( | uint8_t | id | ) |
The function that removes id from the Sync Read list.
id | Dynamixel ID |
Definition at line 74 of file group_sync_read.cpp.
int GroupSyncRead::rxPacket | ( | ) |
The function that receives the packet which might be come from the Dynamixel.
Definition at line 121 of file group_sync_read.cpp.
int GroupSyncRead::txPacket | ( | ) |
The function that transmits the Sync Read instruction packet which might be constructed by GroupSyncRead::addParam function.
Definition at line 110 of file group_sync_read.cpp.
int GroupSyncRead::txRxPacket | ( | ) |
The function that transmits and receives the packet which might be come from the Dynamixel.
Definition at line 149 of file group_sync_read.cpp.
|
protected |
Definition at line 44 of file group_sync_read.h.
|
protected |
Definition at line 39 of file group_sync_read.h.
|
protected |
Definition at line 41 of file group_sync_read.h.
|
protected |
Definition at line 43 of file group_sync_read.h.