19 #ifndef DYNAMIXEL_DRIVER_H 20 #define DYNAMIXEL_DRIVER_H 24 #if defined(__OPENCR__) || defined(__OPENCM904__) 27 #elif defined(__linux__) || defined(__APPLE__) 32 #define MAX_DXL_SERIES_NUM 5 33 #define MAX_HANDLER_NUM 5 34 #define MAX_BULK_PARAMETER 20 87 bool init(
const char* device_name =
"/dev/ttyUSB0",
88 uint32_t baud_rate = 57600,
89 const char **log = NULL);
91 bool begin(
const char* device_name =
"/dev/ttyUSB0",
92 uint32_t baud_rate = 57600,
93 const char **log = NULL);
95 bool setPortHandler(
const char *device_name,
const char **log = NULL);
96 bool setBaudrate(uint32_t baud_rate,
const char **log = NULL);
102 const char *
getModelName(uint8_t
id,
const char **log = NULL);
114 uint8_t *get_the_number_of_id,
116 const char **log = NULL);
119 uint8_t *get_the_number_of_id,
120 uint8_t start_number,
122 const char **log = NULL);
124 bool ping(uint8_t
id,
125 uint16_t *get_model_number,
126 const char **log = NULL);
128 bool ping(uint8_t
id,
129 const char **log = NULL);
133 bool reboot(uint8_t
id,
const char **log = NULL);
134 bool reset(uint8_t
id,
const char **log = NULL);
136 bool writeRegister(uint8_t
id, uint16_t address, uint16_t length, uint8_t* data,
const char **log = NULL);
137 bool writeRegister(uint8_t
id,
const char *item_name, int32_t data,
const char **log = NULL);
139 bool writeOnlyRegister(uint8_t
id, uint16_t address, uint16_t length, uint8_t *data,
const char **log = NULL);
140 bool writeOnlyRegister(uint8_t
id,
const char *item_name, int32_t data,
const char **log = NULL);
142 bool readRegister(uint8_t
id, uint16_t address, uint16_t length, uint32_t *data,
const char **log = NULL);
143 bool readRegister(uint8_t
id,
const char *item_name, int32_t *data,
const char **log = NULL);
145 void getParam(int32_t data, uint8_t *param);
150 bool syncWrite(uint8_t index, int32_t *data,
const char **log = NULL);
151 bool syncWrite(uint8_t index, uint8_t *
id, uint8_t id_num, int32_t *data, uint8_t data_num_for_each_id,
const char **log = NULL);
156 bool syncRead(uint8_t index,
const char **log = NULL);
157 bool syncRead(uint8_t index, uint8_t *
id, uint8_t id_num,
const char **log = NULL);
159 bool getSyncReadData(uint8_t index, int32_t *data,
const char **log = NULL);
160 bool getSyncReadData(uint8_t index, uint8_t *
id, uint8_t id_num, int32_t *data,
const char **log = NULL);
161 bool getSyncReadData(uint8_t index, uint8_t *
id, uint8_t id_num, uint16_t address, uint16_t length, int32_t *data,
const char **log = NULL);
165 bool addBulkWriteParam(uint8_t
id, uint16_t address, uint16_t length, int32_t data,
const char **log = NULL);
166 bool addBulkWriteParam(uint8_t
id,
const char *item_name, int32_t data,
const char **log = NULL);
172 bool addBulkReadParam(uint8_t
id, uint16_t address, uint16_t length,
const char **log = NULL);
173 bool addBulkReadParam(uint8_t
id,
const char *item_name,
const char **log = NULL);
175 bool bulkRead(
const char **log = NULL);
178 bool getBulkReadData(uint8_t *
id, uint8_t id_num, uint16_t *address, uint16_t *length, int32_t *data,
const char **log = NULL);
184 bool setTool(uint16_t model_number, uint8_t
id,
const char **log = NULL);
185 uint8_t
getTool(uint8_t
id,
const char **log = NULL);
188 #endif //DYNAMIXEL_DRIVER_H SyncWriteHandler syncWriteHandler_[MAX_HANDLER_NUM]
uint32_t getBaudrate(void)
bool addBulkWriteParam(uint8_t id, uint16_t address, uint16_t length, int32_t data, const char **log=NULL)
bool addBulkReadParam(uint8_t id, uint16_t address, uint16_t length, const char **log=NULL)
dynamixel::GroupBulkRead * groupBulkRead_
const ControlItem * control_item
bool getBulkReadData(int32_t *data, const char **log=NULL)
uint8_t getTheNumberOfSyncWriteHandler(void)
#define MAX_BULK_PARAMETER
dynamixel::GroupSyncWrite * groupSyncWrite
bool setPacketHandler(float protocol_version, const char **log=NULL)
bool init(const char *device_name="/dev/ttyUSB0", uint32_t baud_rate=57600, const char **log=NULL)
dynamixel::PacketHandler * packetHandler_
const ControlItem * control_item
bool syncWrite(uint8_t index, int32_t *data, const char **log=NULL)
bool readRegister(uint8_t id, uint16_t address, uint16_t length, uint32_t *data, const char **log=NULL)
const char * getModelName(uint8_t id, const char **log=NULL)
bool writeRegister(uint8_t id, uint16_t address, uint16_t length, uint8_t *data, const char **log=NULL)
bool clearMultiTurn(uint8_t id, const char **log=NULL)
bool reset(uint8_t id, const char **log=NULL)
SyncReadHandler syncReadHandler_[MAX_HANDLER_NUM]
bool writeOnlyRegister(uint8_t id, uint16_t address, uint16_t length, uint8_t *data, const char **log=NULL)
bool addSyncWriteHandler(uint16_t address, uint16_t length, const char **log=NULL)
bool addSyncReadHandler(uint16_t address, uint16_t length, const char **log=NULL)
bool begin(const char *device_name="/dev/ttyUSB0", uint32_t baud_rate=57600, const char **log=NULL)
uint8_t sync_write_handler_cnt_
const ControlItem * getItemInfo(uint8_t id, const char *item_name, const char **log=NULL)
bool ping(uint8_t id, uint16_t *get_model_number, const char **log=NULL)
bool scan(uint8_t *get_id, uint8_t *get_the_number_of_id, uint8_t range=253, const char **log=NULL)
bool getSyncReadData(uint8_t index, int32_t *data, const char **log=NULL)
DynamixelTool tools_[MAX_DXL_SERIES_NUM]
uint8_t bulk_read_parameter_cnt_
uint8_t getTheNumberOfSyncReadHandler(void)
dynamixel::PortHandler * portHandler_
bool initBulkWrite(const char **log=NULL)
bool clearBulkReadParam(void)
const ModelInfo * getModelInfo(uint8_t id, const char **log=NULL)
dynamixel::GroupBulkWrite * groupBulkWrite_
bool setPortHandler(const char *device_name, const char **log=NULL)
bool initBulkRead(const char **log=NULL)
uint8_t getTheNumberOfBulkReadParam(void)
dynamixel::GroupSyncRead * groupSyncRead
#define MAX_DXL_SERIES_NUM
bool bulkWrite(const char **log=NULL)
const ControlItem * getControlTable(uint8_t id, const char **log=NULL)
bool reboot(uint8_t id, const char **log=NULL)
uint8_t getTheNumberOfControlItem(uint8_t id, const char **log=NULL)
bool bulkRead(const char **log=NULL)
void getParam(int32_t data, uint8_t *param)
bool setTool(uint16_t model_number, uint8_t id, const char **log=NULL)
uint8_t getTool(uint8_t id, const char **log=NULL)
bool syncRead(uint8_t index, const char **log=NULL)
uint16_t getModelNumber(uint8_t id, const char **log=NULL)
uint8_t sync_read_handler_cnt_
float getProtocolVersion(void)
bool setBaudrate(uint32_t baud_rate, const char **log=NULL)
BulkParameter bulk_read_param_[MAX_BULK_PARAMETER]