Class DynamixelDriver

Inheritance Relationships

Derived Type

Class Documentation

class DynamixelDriver

Subclassed by DynamixelWorkbench

Public Functions

DynamixelDriver()
~DynamixelDriver()
bool init(const char *device_name = "/dev/ttyUSB0", uint32_t baud_rate = 57600, const char **log = NULL)
bool begin(const char *device_name = "/dev/ttyUSB0", uint32_t baud_rate = 57600, const char **log = NULL)
bool setPortHandler(const char *device_name, const char **log = NULL)
bool setBaudrate(uint32_t baud_rate, const char **log = NULL)
bool setPacketHandler(float protocol_version, const char **log = NULL)
float getProtocolVersion(void)
uint32_t getBaudrate(void)
const char *getModelName(uint8_t id, const char **log = NULL)
uint16_t getModelNumber(uint8_t id, const char **log = NULL)
const ControlItem *getControlTable(uint8_t id, const char **log = NULL)
const ControlItem *getItemInfo(uint8_t id, const char *item_name, const char **log = NULL)
uint8_t getTheNumberOfControlItem(uint8_t id, const char **log = NULL)
const ModelInfo *getModelInfo(uint8_t id, const char **log = NULL)
uint8_t getTheNumberOfSyncWriteHandler(void)
uint8_t getTheNumberOfSyncReadHandler(void)
uint8_t getTheNumberOfBulkReadParam(void)
bool scan(uint8_t *get_id, uint8_t *get_the_number_of_id, uint8_t range = 253, const char **log = NULL)
bool scan(uint8_t *get_id, uint8_t *get_the_number_of_id, uint8_t start_number, uint8_t end_number, const char **log = NULL)
bool ping(uint8_t id, uint16_t *get_model_number, const char **log = NULL)
bool ping(uint8_t id, const char **log = NULL)
bool clearMultiTurn(uint8_t id, const char **log = NULL)
bool reboot(uint8_t id, const char **log = NULL)
bool reset(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 writeRegister(uint8_t id, const char *item_name, int32_t data, const char **log = NULL)
bool writeOnlyRegister(uint8_t id, uint16_t address, uint16_t length, uint8_t *data, const char **log = NULL)
bool writeOnlyRegister(uint8_t id, const char *item_name, 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)
bool readRegister(uint8_t id, const char *item_name, int32_t *data, const char **log = NULL)
void getParam(int32_t data, uint8_t *param)
bool addSyncWriteHandler(uint16_t address, uint16_t length, const char **log = NULL)
bool addSyncWriteHandler(uint8_t id, const char *item_name, const char **log = NULL)
bool syncWrite(uint8_t index, int32_t *data, const char **log = NULL)
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)
bool addSyncReadHandler(uint16_t address, uint16_t length, const char **log = NULL)
bool addSyncReadHandler(uint8_t id, const char *item_name, const char **log = NULL)
bool syncRead(uint8_t index, const char **log = NULL)
bool syncRead(uint8_t index, uint8_t *id, uint8_t id_num, const char **log = NULL)
bool getSyncReadData(uint8_t index, int32_t *data, const char **log = NULL)
bool getSyncReadData(uint8_t index, uint8_t *id, uint8_t id_num, int32_t *data, const char **log = NULL)
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)
bool initBulkWrite(const char **log = NULL)
bool addBulkWriteParam(uint8_t id, uint16_t address, uint16_t length, int32_t data, const char **log = NULL)
bool addBulkWriteParam(uint8_t id, const char *item_name, int32_t data, const char **log = NULL)
bool bulkWrite(const char **log = NULL)
bool initBulkRead(const char **log = NULL)
bool addBulkReadParam(uint8_t id, uint16_t address, uint16_t length, const char **log = NULL)
bool addBulkReadParam(uint8_t id, const char *item_name, const char **log = NULL)
bool bulkRead(const char **log = NULL)
bool getBulkReadData(int32_t *data, const char **log = NULL)
bool getBulkReadData(uint8_t *id, uint8_t id_num, uint16_t *address, uint16_t *length, int32_t *data, const char **log = NULL)
bool clearBulkReadParam(void)