#include <dynamixel_interface_driver.h>
Public Member Functions | |
DynamixelInterfaceDriver (const std::string &device="/dev/ttyUSB0", int baud=1000000, bool use_legacy_protocol=false, bool use_group_read=true, bool use_group_write=true) | |
bool | getBulkDataportInfo (std::unordered_map< int, DynamixelDataport > &data_map) const |
bool | getBulkDiagnosticInfo (std::unordered_map< int, DynamixelDiagnostic > &diag_map) const |
bool | getBulkState (std::unordered_map< int, DynamixelState > &state_map) const |
bool | getErrorStatus (int servo_id, DynamixelSeriesType type, uint8_t *error) const |
bool | getMaxTorque (int servo_id, DynamixelSeriesType type, uint16_t *max_torque) const |
bool | getModelNumber (int servo_id, uint16_t *model_number) const |
const DynamixelSpec * | getModelSpec (uint model_number) const |
Get pointer to model spec data for given model number. More... | |
std::string | getSeriesName (DynamixelSeriesType type) const |
bool | getTargetTorque (int servo_id, DynamixelSeriesType type, int16_t *target_torque) const |
bool | getTorqueEnabled (int servo_id, DynamixelSeriesType type, bool *torque_enabled) const |
bool | initialise (void) |
bool | ping (int servo_id) const |
bool | readRegisters (int servo_id, uint16_t address, uint16_t length, std::vector< uint8_t > *response) const |
bool | setAngleLimits (int servo_id, DynamixelSeriesType type, int32_t min_angle, int32_t max_angle) const |
bool | setMaxAngleLimit (int servo_id, DynamixelSeriesType type, int32_t angle) const |
bool | setMaxTorque (int servo_id, DynamixelSeriesType type, uint16_t max_torque) const |
bool | setMaxVelocity (int servo_id, DynamixelSeriesType type, uint32_t max_vel) const |
bool | setMinAngleLimit (int servo_id, DynamixelSeriesType type, int32_t angle) const |
bool | setMultiPosition (std::unordered_map< int, SyncData > &position_data) const |
bool | setMultiProfileVelocity (std::unordered_map< int, SyncData > &velocity_data) const |
bool | setMultiTorque (std::unordered_map< int, SyncData > &torque_data) const |
bool | setMultiVelocity (std::unordered_map< int, SyncData > &velocity_data) const |
bool | setOperatingMode (int servo_id, DynamixelSeriesType type, DynamixelControlMode operating_mode) const |
bool | setPositionDerivativeGain (int servo_id, DynamixelSeriesType type, uint16_t gain) const |
bool | setPositionIntegralGain (int servo_id, DynamixelSeriesType type, uint16_t gain) const |
bool | setPositionPIDGains (int servo_id, DynamixelSeriesType type, double p_gain, double i_gain, double d_gain) const |
bool | setPositionProportionalGain (int servo_id, DynamixelSeriesType type, uint16_t gain) const |
bool | setProfileVelocity (int servo_id, DynamixelSeriesType type, int32_t velocity) const |
bool | setTorque (int servo_id, DynamixelSeriesType type, int16_t torque) const |
bool | setTorqueControlEnabled (int servo_id, DynamixelSeriesType type, bool on) const |
bool | setTorqueEnabled (int servo_id, DynamixelSeriesType type, bool on) const |
bool | setVelocityIntegralGain (int servo_id, DynamixelSeriesType type, uint16_t gain) const |
bool | setVelocityPIDGains (int servo_id, DynamixelSeriesType type, double p_gain, double i_gain) const |
bool | setVelocityProportionalGain (int servo_id, DynamixelSeriesType type, uint16_t gain) const |
bool | writeRegisters (int servo_id, uint16_t address, uint16_t length, uint8_t *data) const |
~DynamixelInterfaceDriver () | |
Destructor. Closes and releases serial port. More... | |
Private Member Functions | |
bool | bulkRead (std::unordered_map< int, SyncData *> &read_data, uint16_t address, uint16_t length) const |
bool | loadMotorData (void) |
bool | syncRead (std::unordered_map< int, SyncData *> &read_data, uint16_t address, uint16_t length) const |
bool | syncWrite (std::unordered_map< int, SyncData > &write_data, uint16_t address, uint16_t length) const |
Private Attributes | |
int | baud_rate_ |
baud rate More... | |
std::string | device_ |
name of device to open More... | |
bool | initialised_ = false |
Variable to indicate if we're ready for comms. More... | |
std::unordered_map< uint16_t, const DynamixelSpec > | model_specs_ |
map of model numbers to motor specifications More... | |
std::unique_ptr< dynamixel::PacketHandler > | packetHandler_ |
packet handler. Provides raw response deconstruction. More... | |
std::unique_ptr< dynamixel::PortHandler > | portHandler_ |
The port handler object. The dynamixel sdk serial object. More... | |
std::unordered_map< int, std::vector< uint8_t > > | raw_read_map_ |
map to store raw reads into More... | |
uint8_t | single_read_fallback_counter_ |
indicates group comm failure fallback interval More... | |
bool | use_group_read_ |
using monolothic bulkRead or syncRead for bulk data exchange More... | |
bool | use_group_write_ |
using monolothic syncWrite for bulk data exchange More... | |
bool | use_legacy_protocol_ |
if we are using legacy 1.0 protocol or newer 2.0 protocol (depends on model support) More... | |
Provides the handling of the low level communications between the dynamixels and the controller
Definition at line 146 of file dynamixel_interface_driver.h.
dynamixel_interface::DynamixelInterfaceDriver::DynamixelInterfaceDriver | ( | const std::string & | device = "/dev/ttyUSB0" , |
int | baud = 1000000 , |
||
bool | use_legacy_protocol = false , |
||
bool | use_group_read = true , |
||
bool | use_group_write = true |
||
) |
Constructor.
[in] | device | The serial port to connect to |
[in] | baud | The baud rate to use |
Definition at line 95 of file dynamixel_interface_driver.cpp.
dynamixel_interface::DynamixelInterfaceDriver::~DynamixelInterfaceDriver | ( | ) |
Destructor. Closes and releases serial port.
Definition at line 143 of file dynamixel_interface_driver.cpp.
|
private |
Performs the bulk read for each protocol. A bulk read is a broadcast instruction on a bus that commands a list of dynamixels to respond in order with a read of a specified address and length (which can be different for each dynamixel). This protocol can be used to read many parameters from many dynamixels on a bus in just one instruction.
[in] | read_data | Pointer to a map of SyncData objects, containing ids and vectors to read into |
[in] | address | The address value in the control table the dynamixels will start reading from |
[in] | length | The number of bytes to read consecutively from the control table |
Definition at line 1049 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::getBulkDataportInfo | ( | std::unordered_map< int, DynamixelDataport > & | data_map | ) | const |
Bulk Reads the voltage and temperature in one instruction, behaves the same as getBulkState()
[in] | data_map | map of servo ids to dataport objects to read into |
Definition at line 742 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::getBulkDiagnosticInfo | ( | std::unordered_map< int, DynamixelDiagnostic > & | diag_map | ) | const |
Bulk Reads the voltage and temperature in one instruction, behaves the same as getBulkState()
[in] | diag_map | map of servo ids to diagnostics objects to read into |
Definition at line 876 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::getBulkState | ( | std::unordered_map< int, DynamixelState > & | state_map | ) | const |
Bulk Reads the Present Position, Present Velocity and Present Current in one instruction. If the group read fails the function will fall back on reading each motor individually. Optionally, the group comms can be disabled on initialisation of the driver (by setting use_group_read to false) in which case the function will always read from each dynamixel individually.
[in] | state_map | map of servo ids to state data to read into |
Definition at line 574 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::getErrorStatus | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
uint8_t * | error_status | ||
) | const |
Retrieves the hardware status error value from the dynamixel's eeprom
[in] | servo_id | The ID of the servo to retrieve from |
[in] | type | the type of the servo to read from |
[out] | error | Stores the returned error code |
Definition at line 342 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::getMaxTorque | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
uint16_t * | max_torque | ||
) | const |
Retrieves the maximum torque limit from the dynamixel's eeprom.
[in] | servo_id | The ID of the servo to retrieve from |
[in] | type | the type of the servo to read from |
[out] | max_torque | Stores the value returned |
Definition at line 392 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::getModelNumber | ( | int | servo_id, |
uint16_t * | model_number | ||
) | const |
Retrieves the model number from the dynamixel's eeprom
[in] | servo_id | The ID of the servo to retrieve from |
[out] | model_number | Stores the model_number returned |
Definition at line 318 of file dynamixel_interface_driver.cpp.
|
inline |
Get pointer to model spec data for given model number.
Definition at line 171 of file dynamixel_interface_driver.h.
|
inline |
Returns a string version of the dynamixel series based on the input type
[in] | type | the type of the servo to read from |
Definition at line 435 of file dynamixel_interface_driver.h.
bool dynamixel_interface::DynamixelInterfaceDriver::getTargetTorque | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
int16_t * | target_torque | ||
) | const |
Retrieves the current target_velocity from the dynamixel's ram.
[in] | servo_id | The ID of the servo to retrieve from |
[in] | type | the type of the servo to read from |
[out] | target_velocity | Stores the value returned |
Definition at line 493 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::getTorqueEnabled | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
bool * | torque_enabled | ||
) | const |
Retrieves the torque enabled value from the dynamixel's ram.
[in] | servo_id | The ID of the servo to retrieve from |
[in] | type | the type of the servo to read from |
[out] | torque_enabled | Stores the status of torque enable |
Definition at line 442 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::initialise | ( | void | ) |
Parses Motor Data, Opens port and sets up driver
Definition at line 259 of file dynamixel_interface_driver.cpp.
|
private |
Loads in the motor specifications from the motor_data.yaml file
Definition at line 153 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::ping | ( | int | servo_id | ) | const |
Ping the specified id, used to check if a dynamixel with that ID is on the bus
[in] | servo_id | The ID to ping on the bus. |
Definition at line 295 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::readRegisters | ( | int | servo_id, |
uint16_t | address, | ||
uint16_t | length, | ||
std::vector< uint8_t > * | response | ||
) | const |
Retrieves arbitrary register readings from the Dynamixel, can be used in cases where provided getters are insufficient or to read multiple contiguous values at once.
[in] | servo_id | The ID of the servo to retrieve from |
[in] | address | The address value in the control table the dynamixel will start reading from |
[in] | length | The number of bytes to read consecutively from the control table |
[out] | response | Array to store the raw dynamixel response. |
Definition at line 544 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setAngleLimits | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
int32_t | min_angle, | ||
int32_t | max_angle | ||
) | const |
Sets the minimum and maximum angle limits for the dynamixel
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | min_angle | the minimum angle limit (in encoder values) |
[in] | max_angle | the maximum angle limit (in encoder values) |
Definition at line 1279 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setMaxAngleLimit | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
int32_t | angle | ||
) | const |
Sets the maximum angle limit for the dynamixel
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | angle | The maximum angle limit (in encoder values) |
Definition at line 1346 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setMaxTorque | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
uint16_t | max_torque | ||
) | const |
Sets the maximum torque limit for the dynamixel
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | max_torque | the maximum torque limit |
Definition at line 1395 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setMaxVelocity | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
uint32_t | max_vel | ||
) | const |
Sets the maximum velocity limit for the dynamixel
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | max_vel | the maximum velocity limit |
Definition at line 1450 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setMinAngleLimit | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
int32_t | angle | ||
) | const |
Sets the minimum angle limit for the dynamixel
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | angle | The minimum angle limit (in encoder values) |
Definition at line 1297 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setMultiPosition | ( | std::unordered_map< int, SyncData > & | position_data | ) | const |
Set many dynamixels with new position values in one instruction.
[in] | position_data | map of ids to syncdata objects containing position data |
Definition at line 2070 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setMultiProfileVelocity | ( | std::unordered_map< int, SyncData > & | velocity_data | ) | const |
Set many dynamixels with new profile velocity values in one instruction.
[in] | velocity_data | map of ids to syncdata objects containing profile velocity data |
Definition at line 2137 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setMultiTorque | ( | std::unordered_map< int, SyncData > & | torque_data | ) | const |
Set many dynamixels with new torque values in one instruction.
[in] | torque_data | map of ids to syncdata objects containing torque data |
Definition at line 2170 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setMultiVelocity | ( | std::unordered_map< int, SyncData > & | velocity_data | ) | const |
Set many dynamixels with new position values in one instruction.
[in] | velocity_data | map of ids to syncdata objects containing velocity data |
Definition at line 2104 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setOperatingMode | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
DynamixelControlMode | operating_mode | ||
) | const |
Sets the Operating mode of the Dynamixel. The three possible control modes are: Position, Velocity or Torque. The way these modes are enabled differs for each series of dynamixel. XM and Pro have an operating mode register that can be used to changed the control type. For AX, RX and MX series, the method of control is defined by the values in the angle limit registers and the torque_control_enable register. Note torque control is not available on the MX-28 models.
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | operating_mode | The method of control |
Definition at line 1185 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setPositionDerivativeGain | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
uint16_t | gain | ||
) | const |
Sets the derivative gain value for the position control mode if available.
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | gain | The derivative gain value to write |
Definition at line 1751 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setPositionIntegralGain | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
uint16_t | gain | ||
) | const |
Sets the integral gain value for the position control mode if available.
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | gain | The integral gain value to write |
Definition at line 1702 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setPositionPIDGains | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
double | p_gain, | ||
double | i_gain, | ||
double | d_gain | ||
) | const |
The following functions set the PID gains for the dynamixel. note that the PID gains are available based on series and control type:
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | p_gain | The proportional gain value to write |
[in] | i_gain | The integral gain value to write |
[in] | d_gain | The derivative gain value to write |
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | p_gain | The proportional gain value to write |
[in] | i_gain | The integral gain value to write |
[in] | d_gain | The derivative gain value to write |
Definition at line 1585 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setPositionProportionalGain | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
uint16_t | gain | ||
) | const |
Sets the proportional gain value for the position control mode if available.
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | gain | The proportional gain value to write |
Definition at line 1651 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setProfileVelocity | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
int32_t | velocity | ||
) | const |
Sets the profile velocity of the dynamixel. Profile velocity is how fast the servo should move between positions.
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | velocity | The profile velocity value to write |
Definition at line 1944 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setTorque | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
int16_t | torque | ||
) | const |
Sets the torque value of the dynamixel.
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | torque | The torque value to write |
Definition at line 1994 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setTorqueControlEnabled | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
bool | on | ||
) | const |
Sets the torque control enable register of the dynamixel mx series. can be used to dynamically switch between position and torque control modes.
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | on | The torque control state of the servo (true = on, false = off). |
Definition at line 1549 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setTorqueEnabled | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
bool | on | ||
) | const |
Sets the torque enable register of the dynamixel. This value defines the on/off state of the servo.
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | on | The state of the servo (true = on, false = off). |
Definition at line 1498 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setVelocityIntegralGain | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
uint16_t | gain | ||
) | const |
Sets the integral gain value for the velocity control mode if available.
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | gain | The integral gain value to write |
Definition at line 1898 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setVelocityPIDGains | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
double | p_gain, | ||
double | i_gain | ||
) | const |
Sets the velocity PID values for the dynamixels
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | p_gain | The proportional gain value to write |
[in] | i_gain | The integral gain value to write |
[in] | d_gain | The derivative gain value to write |
Definition at line 1802 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::setVelocityProportionalGain | ( | int | servo_id, |
DynamixelSeriesType | type, | ||
uint16_t | gain | ||
) | const |
Sets the proportional gain value for the velocity control mode if available.
[in] | servo_id | The ID of the servo to write to |
[in] | type | the type of the servo to read from |
[in] | gain | The proportional gain value to write |
Definition at line 1852 of file dynamixel_interface_driver.cpp.
|
private |
Performs the sync read for each protocol. A sync read is a broadcast instruction on a bus that commands a list of dynamixels to respond in order with a read of a specified address and length. This protocol can be used to read many parameters from many dynamixels on a bus in just one instruction.
[in] | read_data | Pointer to a map of SyncData objects, containing ids and vectors to read into |
[in] | address | The address value in the control table the dynamixels will start reading from |
[in] | length | The number of bytes to read consecutively from the control table |
Definition at line 1111 of file dynamixel_interface_driver.cpp.
|
private |
Performs the sync write for each protocol. A sync write is a broadcast instruction on a bus that commands a list of dynamixels to write a value into a specified address (the value written can be different for each dynamixel but the address is universal). This can be used to update a parameter (say goal position) for many dynamixels, each with a unique value, all in one instruction.
[in] | write_data | Pointer to a map of SyncData objects, containing ids and vectors to write from. |
[in] | address | The address value in the control table the dynamixels will write to |
[in] | length | The number of bytes to write |
Definition at line 2211 of file dynamixel_interface_driver.cpp.
bool dynamixel_interface::DynamixelInterfaceDriver::writeRegisters | ( | int | servo_id, |
uint16_t | address, | ||
uint16_t | length, | ||
uint8_t * | data | ||
) | const |
Writes arbitrary register values to the Dynamixel, can be used in cases where provided setters are insufficient or to write multiple contiguous values at once.
[in] | servo_id | The ID of the servo to write to |
[in] | address | The address value in the control table the dynamixel will start writing to |
[in] | length | The number of bytes to write consecutively to the control table |
[in] | data | Array containing the value to be written. |
Definition at line 2046 of file dynamixel_interface_driver.cpp.
|
private |
baud rate
Definition at line 510 of file dynamixel_interface_driver.h.
|
private |
name of device to open
Definition at line 509 of file dynamixel_interface_driver.h.
|
private |
Variable to indicate if we're ready for comms.
Definition at line 516 of file dynamixel_interface_driver.h.
|
private |
map of model numbers to motor specifications
Definition at line 519 of file dynamixel_interface_driver.h.
|
private |
packet handler. Provides raw response deconstruction.
Definition at line 507 of file dynamixel_interface_driver.h.
|
private |
The port handler object. The dynamixel sdk serial object.
Definition at line 506 of file dynamixel_interface_driver.h.
|
private |
map to store raw reads into
Definition at line 520 of file dynamixel_interface_driver.h.
|
private |
indicates group comm failure fallback interval
Definition at line 517 of file dynamixel_interface_driver.h.
|
private |
using monolothic bulkRead or syncRead for bulk data exchange
Definition at line 513 of file dynamixel_interface_driver.h.
|
private |
using monolothic syncWrite for bulk data exchange
Definition at line 514 of file dynamixel_interface_driver.h.
|
private |
if we are using legacy 1.0 protocol or newer 2.0 protocol (depends on model support)
Definition at line 512 of file dynamixel_interface_driver.h.