#include <dynamixel_workbench.h>

Public Member Functions | |
| bool | changeBaudrate (uint8_t id, uint32_t new_baudrate, const char **log=NULL) |
| bool | changeID (uint8_t id, uint8_t new_id, const char **log=NULL) |
| bool | changeProtocolVersion (uint8_t id, uint8_t version, const char **log=NULL) |
| int16_t | convertCurrent2Value (uint8_t id, float current) |
| int16_t | convertCurrent2Value (float current) |
| int32_t | convertRadian2Value (uint8_t id, float radian) |
| int32_t | convertRadian2Value (float radian, int32_t max_position, int32_t min_position, float max_radian, float min_radian) |
| float | convertValue2Current (uint8_t id, int16_t value) |
| float | convertValue2Current (int16_t value) |
| float | convertValue2Load (int16_t value) |
| float | convertValue2Radian (uint8_t id, int32_t value) |
| float | convertValue2Radian (int32_t value, int32_t max_position, int32_t min_position, float max_radian, float min_radian) |
| float | convertValue2Velocity (uint8_t id, int32_t value) |
| int32_t | convertVelocity2Value (uint8_t id, float velocity) |
| bool | currentBasedPositionMode (uint8_t id, int32_t current=0, const char **log=NULL) |
| DynamixelWorkbench () | |
| bool | getPresentPositionData (uint8_t id, int32_t *data, const char **log=NULL) |
| bool | getPresentVelocityData (uint8_t id, int32_t *data, const char **log=NULL) |
| bool | getRadian (uint8_t id, float *radian, const char **log=NULL) |
| bool | getVelocity (uint8_t id, float *velocity, const char **log=NULL) |
| bool | goalPosition (uint8_t id, int value, const char **log=NULL) |
| bool | goalPosition (uint8_t id, float radian, const char **log=NULL) |
| bool | goalSpeed (uint8_t id, int value, const char **log=NULL) |
| bool | goalVelocity (uint8_t id, int value, const char **log=NULL) |
| bool | goalVelocity (uint8_t id, float velocity, const char **log=NULL) |
| bool | itemRead (uint8_t id, const char *item_name, int32_t *data, const char **log=NULL) |
| bool | itemWrite (uint8_t id, const char *item_name, int32_t data, const char **log=NULL) |
| bool | jointMode (uint8_t id, int32_t velocity=0, int32_t acceleration=0, const char **log=NULL) |
| bool | led (uint8_t id, int32_t onoff, const char **log=NULL) |
| bool | ledOff (uint8_t id, const char **log=NULL) |
| bool | ledOn (uint8_t id, const char **log=NULL) |
| bool | setCurrentBasedPositionControlMode (uint8_t id, const char **log=NULL) |
| bool | setCurrentControlMode (uint8_t id, const char **log=NULL) |
| bool | setExtendedPositionControlMode (uint8_t id, const char **log=NULL) |
| bool | setMultiTurnControlMode (uint8_t id, const char **log=NULL) |
| bool | setNormalDirection (uint8_t id, const char **log=NULL) |
| bool | setOperatingMode (uint8_t id, uint8_t index, const char **log=NULL) |
| bool | setPositionControlMode (uint8_t id, const char **log=NULL) |
| bool | setPWMControlMode (uint8_t id, const char **log=NULL) |
| bool | setReverseDirection (uint8_t id, const char **log=NULL) |
| bool | setSecondaryID (uint8_t id, uint8_t secondary_id, const char **log=NULL) |
| bool | setTimeBasedProfile (uint8_t id, const char **log=NULL) |
| bool | setTorqueControlMode (uint8_t id, const char **log=NULL) |
| bool | setVelocityBasedProfile (uint8_t id, const char **log=NULL) |
| bool | setVelocityControlMode (uint8_t id, const char **log=NULL) |
| bool | torque (uint8_t id, int32_t onoff, const char **log=NULL) |
| bool | torqueOff (uint8_t id, const char **log=NULL) |
| bool | torqueOn (uint8_t id, const char **log=NULL) |
| bool | wheelMode (uint8_t id, int32_t acceleration=0, const char **log=NULL) |
| ~DynamixelWorkbench () | |
Public Member Functions inherited from DynamixelDriver | |
| 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 | 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 | 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 | 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 | begin (const char *device_name="/dev/ttyUSB0", uint32_t baud_rate=57600, const char **log=NULL) |
| bool | bulkRead (const char **log=NULL) |
| bool | bulkWrite (const char **log=NULL) |
| bool | clearBulkReadParam (void) |
| bool | clearMultiTurn (uint8_t id, const char **log=NULL) |
| DynamixelDriver () | |
| uint32_t | getBaudrate (void) |
| 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) |
| const ControlItem * | getControlTable (uint8_t id, const char **log=NULL) |
| const ControlItem * | getItemInfo (uint8_t id, const char *item_name, const char **log=NULL) |
| const ModelInfo * | getModelInfo (uint8_t id, const char **log=NULL) |
| const char * | getModelName (uint8_t id, const char **log=NULL) |
| uint16_t | getModelNumber (uint8_t id, const char **log=NULL) |
| void | getParam (int32_t data, uint8_t *param) |
| float | getProtocolVersion (void) |
| 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) |
| uint8_t | getTheNumberOfBulkReadParam (void) |
| uint8_t | getTheNumberOfControlItem (uint8_t id, const char **log=NULL) |
| uint8_t | getTheNumberOfSyncReadHandler (void) |
| uint8_t | getTheNumberOfSyncWriteHandler (void) |
| bool | init (const char *device_name="/dev/ttyUSB0", uint32_t baud_rate=57600, const char **log=NULL) |
| bool | initBulkRead (const char **log=NULL) |
| bool | initBulkWrite (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 | 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) |
| bool | reboot (uint8_t id, const char **log=NULL) |
| bool | reset (uint8_t id, 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 | 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 | setBaudrate (uint32_t baud_rate, const char **log=NULL) |
| bool | setPacketHandler (float protocol_version, const char **log=NULL) |
| bool | setPortHandler (const char *device_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 | 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 | 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 | 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) |
| ~DynamixelDriver () | |
Definition at line 24 of file dynamixel_workbench.h.
| DynamixelWorkbench::DynamixelWorkbench | ( | ) |
Definition at line 36 of file dynamixel_workbench.cpp.
| DynamixelWorkbench::~DynamixelWorkbench | ( | ) |
Definition at line 38 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::changeBaudrate | ( | uint8_t | id, |
| uint32_t | new_baudrate, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 92 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::changeID | ( | uint8_t | id, |
| uint8_t | new_id, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 73 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::changeProtocolVersion | ( | uint8_t | id, |
| uint8_t | version, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 217 of file dynamixel_workbench.cpp.
| int16_t DynamixelWorkbench::convertCurrent2Value | ( | uint8_t | id, |
| float | current | ||
| ) |
Definition at line 1337 of file dynamixel_workbench.cpp.
| int16_t DynamixelWorkbench::convertCurrent2Value | ( | float | current | ) |
Definition at line 1371 of file dynamixel_workbench.cpp.
| int32_t DynamixelWorkbench::convertRadian2Value | ( | uint8_t | id, |
| float | radian | ||
| ) |
Definition at line 1173 of file dynamixel_workbench.cpp.
| int32_t DynamixelWorkbench::convertRadian2Value | ( | float | radian, |
| int32_t | max_position, | ||
| int32_t | min_position, | ||
| float | max_radian, | ||
| float | min_radian | ||
| ) |
Definition at line 1215 of file dynamixel_workbench.cpp.
| float DynamixelWorkbench::convertValue2Current | ( | uint8_t | id, |
| int16_t | value | ||
| ) |
Definition at line 1381 of file dynamixel_workbench.cpp.
| float DynamixelWorkbench::convertValue2Current | ( | int16_t | value | ) |
Definition at line 1422 of file dynamixel_workbench.cpp.
| float DynamixelWorkbench::convertValue2Load | ( | int16_t | value | ) |
Definition at line 1432 of file dynamixel_workbench.cpp.
| float DynamixelWorkbench::convertValue2Radian | ( | uint8_t | id, |
| int32_t | value | ||
| ) |
Definition at line 1196 of file dynamixel_workbench.cpp.
| float DynamixelWorkbench::convertValue2Radian | ( | int32_t | value, |
| int32_t | max_position, | ||
| int32_t | min_position, | ||
| float | max_radian, | ||
| float | min_radian | ||
| ) |
Definition at line 1236 of file dynamixel_workbench.cpp.
| float DynamixelWorkbench::convertValue2Velocity | ( | uint8_t | id, |
| int32_t | value | ||
| ) |
Definition at line 1296 of file dynamixel_workbench.cpp.
| int32_t DynamixelWorkbench::convertVelocity2Value | ( | uint8_t | id, |
| float | velocity | ||
| ) |
Definition at line 1253 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::currentBasedPositionMode | ( | uint8_t | id, |
| int32_t | current = 0, |
||
| const char ** | log = NULL |
||
| ) |
Definition at line 928 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::getPresentPositionData | ( | uint8_t | id, |
| int32_t * | data, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 1102 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::getPresentVelocityData | ( | uint8_t | id, |
| int32_t * | data, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 1156 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::getRadian | ( | uint8_t | id, |
| float * | radian, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 1120 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::getVelocity | ( | uint8_t | id, |
| float * | velocity, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 1138 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::goalPosition | ( | uint8_t | id, |
| int | value, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 966 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::goalPosition | ( | uint8_t | id, |
| float | radian, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 1066 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::goalSpeed | ( | uint8_t | id, |
| int | value, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 988 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::goalVelocity | ( | uint8_t | id, |
| int | value, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 996 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::goalVelocity | ( | uint8_t | id, |
| float | velocity, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 1084 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::itemRead | ( | uint8_t | id, |
| const char * | item_name, | ||
| int32_t * | data, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 253 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::itemWrite | ( | uint8_t | id, |
| const char * | item_name, | ||
| int32_t | data, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 248 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::jointMode | ( | uint8_t | id, |
| int32_t | velocity = 0, |
||
| int32_t | acceleration = 0, |
||
| const char ** | log = NULL |
||
| ) |
Definition at line 783 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::led | ( | uint8_t | id, |
| int32_t | onoff, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 258 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::ledOff | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 282 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::ledOn | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 273 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setCurrentBasedPositionControlMode | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 554 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setCurrentControlMode | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 490 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setExtendedPositionControlMode | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 522 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setMultiTurnControlMode | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 538 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setNormalDirection | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 291 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setOperatingMode | ( | uint8_t | id, |
| uint8_t | index, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 586 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setPositionControlMode | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 458 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setPWMControlMode | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 570 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setReverseDirection | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 324 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setSecondaryID | ( | uint8_t | id, |
| uint8_t | secondary_id, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 423 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setTimeBasedProfile | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 390 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setTorqueControlMode | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 506 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setVelocityBasedProfile | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 357 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::setVelocityControlMode | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 474 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::torque | ( | uint8_t | id, |
| int32_t | onoff, | ||
| const char ** | log = NULL |
||
| ) |
Definition at line 40 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::torqueOff | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 64 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::torqueOn | ( | uint8_t | id, |
| const char ** | log = NULL |
||
| ) |
Definition at line 55 of file dynamixel_workbench.cpp.
| bool DynamixelWorkbench::wheelMode | ( | uint8_t | id, |
| int32_t | acceleration = 0, |
||
| const char ** | log = NULL |
||
| ) |
Definition at line 866 of file dynamixel_workbench.cpp.