Class GroupSyncRead
- Defined in File group_sync_read.h 
Class Documentation
- 
class GroupSyncRead
- The class for reading multiple Dynamixel data from same address with same length at once. - Public Functions - 
GroupSyncRead(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length)
- The function that Initializes instance for Sync Read. - Parameters:
- port – PortHandler instance 
- ph – PacketHandler instance 
- start_address – Address of the data for read 
- data_length – Length of the data for read 
 
 
 - 
inline ~GroupSyncRead()
- The function that calls clearParam function to clear the parameter list for Sync Read. 
 - 
inline PortHandler *getPortHandler()
- The function that returns PortHandler instance. - Returns:
- PortHandler instance 
 
 - 
inline PacketHandler *getPacketHandler()
- The function that returns PacketHandler instance. - Returns:
- PacketHandler instance 
 
 - 
bool addParam(uint8_t id)
- The function that adds id, start_address, data_length to the Sync Read list. - Parameters:
- id – Dynamixel ID 
- Returns:
- false 
- Returns:
- when the ID exists already in the list 
- Returns:
- when the protocol1.0 has been used 
- Returns:
- or true 
 
 - 
void removeParam(uint8_t id)
- The function that removes id from the Sync Read list. - Parameters:
- id – Dynamixel ID 
 
 - 
void clearParam()
- The function that clears the Sync Read list. 
 - 
int txPacket()
- The function that transmits the Sync Read instruction packet which might be constructed by GroupSyncRead::addParam function. - Returns:
- COMM_NOT_AVAILABLE 
- Returns:
- when the list for Sync Read is empty 
- Returns:
- when the protocol1.0 has been used 
- Returns:
- or the other communication results which come from PacketHandler::syncReadTx 
 
 - 
int rxPacket()
- The function that receives the packet which might be come from the Dynamixel. - Returns:
- COMM_NOT_AVAILABLE 
- Returns:
- when the list for Sync Read is empty 
- Returns:
- when the protocol1.0 has been used 
- Returns:
- COMM_SUCCESS 
- Returns:
- when there is packet recieved 
- Returns:
- or the other communication results 
 
 - 
int txRxPacket()
- The function that transmits and receives the packet which might be come from the Dynamixel. - Returns:
- COMM_NOT_AVAILABLE 
- Returns:
- when the protocol1.0 has been used 
- Returns:
- COMM_RX_FAIL 
- Returns:
- when there is no packet recieved 
- Returns:
- COMM_SUCCESS 
- Returns:
- when there is packet recieved 
- Returns:
- or the other communication results which come from GroupBulkRead::txPacket or GroupBulkRead::rxPacket 
 
 - 
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. - Parameters:
- id – Dynamixel ID 
- address – Address of the data for read 
- data_length – Length of the data for read 
 
- Returns:
- false 
- Returns:
- when there are no data available 
- Returns:
- when the protocol1.0 has been used 
- Returns:
- or true 
 
 - 
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. - Parameters:
- id – Dynamixel ID 
- address – Address of the data for read @data_length Length of the data for read 
 
- Returns:
- data value 
 
 - 
bool getError(uint8_t id, uint8_t *error)
- The function that gets the error which might be received by GroupSyncRead::rxPacket or GroupSyncRead::txRxPacket. - Parameters:
- id – Dynamixel ID @error error of Dynamixel 
- Returns:
- true 
- Returns:
- when Dynamixel returned specific error byte 
- Returns:
- or false 
 
 
- 
GroupSyncRead(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length)