21 #if defined(__linux__) 23 #elif defined(__APPLE__) 25 #elif defined(_WIN32) || defined(_WIN64) 28 #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) 29 #include "../../include/dynamixel_sdk/group_sync_read.h" 38 is_param_changed_(false),
40 start_address_(start_address),
41 data_length_(data_length)
58 for (
unsigned int i = 0; i <
id_list_.size(); i++)
82 std::vector<uint8_t>::iterator it = std::find(
id_list_.begin(),
id_list_.end(), id);
99 for (
unsigned int i = 0; i <
id_list_.size(); i++)
137 for (
int i = 0; i < cnt; i++)
179 if (
isAvailable(
id, address, data_length) ==
false)
#define DXL_MAKEDWORD(a, b)
void clearParam()
The function that clears the Sync Read list.
int txRxPacket()
The function that transmits and receives the packet which might be come from the Dynamixel.
std::map< uint8_t, uint8_t * > data_list_
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::r...
int rxPacket()
The function that receives the packet which might be come from the Dynamixel.
#define DXL_MAKEWORD(a, b)
bool addParam(uint8_t id)
The function that adds id, start_address, data_length to the Sync Read list.
void removeParam(uint8_t id)
The function that removes id from the Sync Read list.
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::...
int txPacket()
The function that transmits the Sync Read instruction packet which might be constructed by GroupSyncR...
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
bool getError(uint8_t id, uint8_t *error)
The function that gets the error which might be received by GroupSyncRead::rxPacket or GroupSyncRead:...
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...
#define COMM_NOT_AVAILABLE
std::vector< uint8_t > id_list_
std::map< uint8_t, uint8_t * > error_list_
virtual int syncReadTx(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length)=0
The function that transmits INST_SYNC_READ instruction packet The function makes an instruction pack...
GroupSyncRead(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length)
The function that Initializes instance for Sync Read.