22 #if defined(__linux__) 24 #elif defined(__APPLE__) 26 #elif defined(_WIN32) || defined(_WIN64) 29 #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) 30 #include "../../include/dynamixel_sdk/group_bulk_read.h" 39 is_param_changed_(false),
64 for (
unsigned int i = 0; i <
id_list_.size(); i++)
101 std::vector<uint8_t>::iterator it = std::find(
id_list_.begin(),
id_list_.end(), id);
121 for (
unsigned int i = 0; i <
id_list_.size(); i++)
165 for (
int i = 0; i < cnt; i++)
200 if (address < start_addr || start_addr +
length_list_[
id] - data_length < address)
208 if (
isAvailable(
id, address, data_length) ==
false)
#define DXL_MAKEDWORD(a, b)
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 GroupBulkRead::r...
std::map< uint8_t, uint16_t > length_list_
int txPacket()
The function that transmits the Bulk Read instruction packet which might be constructed by GroupBulkR...
bool addParam(uint8_t id, uint16_t start_address, uint16_t data_length)
The function that adds id, start_address, data_length to the Bulk Read list.
#define DXL_MAKEWORD(a, b)
int rxPacket()
The function that receives the packet which might be come from the Dynamixel.
void clearParam()
The function that clears the Bulk Read list.
void removeParam(uint8_t id)
The function that removes id from the Bulk Read list.
virtual int bulkReadTx(PortHandler *port, uint8_t *param, uint16_t param_length)=0
The function that transmits INST_BULK_READ instruction packet The function makes an instruction pack...
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
std::map< uint8_t, uint16_t > address_list_
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac, or PortHandlerArduino.
virtual float getProtocolVersion()=0
The function that returns Protocol version.
virtual int readRx(PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error=0)=0
The function that receives the packet and reads the data in the packet The function receives the pac...
uint32_t getData(uint8_t id, uint16_t address, uint16_t data_length)
The function that gets the data which might be received by GroupBulkRead::rxPacket or GroupBulkRead::...
std::vector< uint8_t > id_list_
std::map< uint8_t, uint8_t * > error_list_
#define COMM_NOT_AVAILABLE
GroupBulkRead(PortHandler *port, PacketHandler *ph)
The function that Initializes instance for Bulk Read.
std::map< uint8_t, uint8_t * > data_list_
int txRxPacket()
The function that transmits and receives the packet which might be come from the Dynamixel.
bool getError(uint8_t id, uint8_t *error)
The function that gets the error which might be received by GroupBulkRead::rxPacket or GroupBulkRead:...