22 #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKREAD_H_ 23 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKREAD_H_ 90 bool addParam (uint8_t
id, uint16_t start_address, uint16_t data_length);
96 void removeParam (uint8_t
id);
142 bool isAvailable (uint8_t
id, uint16_t address, uint16_t data_length);
151 uint32_t getData (uint8_t
id, uint16_t address, uint16_t data_length);
161 bool getError (uint8_t
id, uint8_t* error);
std::map< uint8_t, uint16_t > length_list_
PortHandler * getPortHandler()
The function that returns PortHandler instance.
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
std::map< uint8_t, uint16_t > address_list_
PacketHandler * getPacketHandler()
The function that returns PacketHandler instance.
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac, or PortHandlerArduino.
The class for reading multiple Dynamixel data from different addresses with different lengths at once...
std::vector< uint8_t > id_list_
~GroupBulkRead()
The function that calls clearParam function to clear the parameter list for Bulk Read.
std::map< uint8_t, uint8_t * > error_list_
std::map< uint8_t, uint8_t * > data_list_