21 #if defined(__linux__)
22 #include "../../include/mercury_sdk/group_sync_read.h"
23 #elif defined(__APPLE__)
25 #elif defined(_WIN32) || defined(_WIN64)
28 #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB)
29 #include "../../include/mercury_sdk/group_sync_read.h"
37 start_address_(start_address),
38 data_length_(data_length)
55 for (
unsigned int i = 0; i <
id_list_.size(); i++)
79 std::vector<uint8_t>::iterator it = std::find(
id_list_.begin(),
id_list_.end(),
id);
96 for (
unsigned int i = 0; i <
id_list_.size(); i++)
134 for (
int i = 0; i < cnt; i++)
176 if (
isAvailable(
id, address, data_length) ==
false)
std::vector< uint8_t > id_list_
std::map< uint8_t, uint8_t * > data_list_
std::map< uint8_t, uint8_t * > error_list_
bool addParam(uint8_t id)
The function that adds id, start_address, data_length to the Sync Read list.
int txPacket()
The function that transmits the Sync Read instruction packet which might be constructed by GroupSyncR...
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 GroupSyncRead::rxPacket or GroupSyncRead:...
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...
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::...
GroupSyncRead(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length)
The function that Initializes instance for Sync Read.
void clearParam()
The function that clears the Sync Read list.
int rxPacket()
The function that receives the packet which might be come from the Dynamixel.
void removeParam(uint8_t id)
The function that removes id from the Sync Read list.
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
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 @description The function rece...
virtual float getProtocolVersion()=0
The function that returns Protocol version.
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 @description The function makes an inst...
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac,...
#define MCY_MAKEDWORD(a, b)
#define COMM_NOT_AVAILABLE
#define MCY_MAKEWORD(a, b)