Public Member Functions | Private Member Functions | Private Attributes | List of all members
dynamixel_interface::DynamixelInterfaceDriver Class Reference

#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 DynamixelSpecgetModelSpec (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 DynamixelSpecmodel_specs_
 map of model numbers to motor specifications More...
 
std::unique_ptr< dynamixel::PacketHandlerpacketHandler_
 packet handler. Provides raw response deconstruction. More...
 
std::unique_ptr< dynamixel::PortHandlerportHandler_
 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...
 

Detailed Description

Provides the handling of the low level communications between the dynamixels and the controller

Definition at line 146 of file dynamixel_interface_driver.h.

Constructor & Destructor Documentation

◆ DynamixelInterfaceDriver()

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.

Parameters
[in]deviceThe serial port to connect to
[in]baudThe baud rate to use

Definition at line 95 of file dynamixel_interface_driver.cpp.

◆ ~DynamixelInterfaceDriver()

dynamixel_interface::DynamixelInterfaceDriver::~DynamixelInterfaceDriver ( )

Destructor. Closes and releases serial port.

Definition at line 143 of file dynamixel_interface_driver.cpp.

Member Function Documentation

◆ bulkRead()

bool dynamixel_interface::DynamixelInterfaceDriver::bulkRead ( std::unordered_map< int, SyncData *> &  read_data,
uint16_t  address,
uint16_t  length 
) const
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.

Parameters
[in]read_dataPointer to a map of SyncData objects, containing ids and vectors to read into
[in]addressThe address value in the control table the dynamixels will start reading from
[in]lengthThe number of bytes to read consecutively from the control table
Returns
true if at least one dynamixel was successfully read

Definition at line 1049 of file dynamixel_interface_driver.cpp.

◆ getBulkDataportInfo()

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()

Parameters
[in]data_mapmap of servo ids to dataport objects to read into
Returns
True on comm success, false otherwise

Definition at line 742 of file dynamixel_interface_driver.cpp.

◆ getBulkDiagnosticInfo()

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()

Parameters
[in]diag_mapmap of servo ids to diagnostics objects to read into
Returns
True on comm success, false otherwise

Definition at line 876 of file dynamixel_interface_driver.cpp.

◆ getBulkState()

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.

Parameters
[in]state_mapmap of servo ids to state data to read into
Returns
True on comm success, false otherwise

Definition at line 574 of file dynamixel_interface_driver.cpp.

◆ getErrorStatus()

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

Parameters
[in]servo_idThe ID of the servo to retrieve from
[in]typethe type of the servo to read from
[out]errorStores the returned error code
Returns
True on comm success, false otherwise.

Definition at line 342 of file dynamixel_interface_driver.cpp.

◆ getMaxTorque()

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.

Parameters
[in]servo_idThe ID of the servo to retrieve from
[in]typethe type of the servo to read from
[out]max_torqueStores the value returned
Returns
True on comm success, false otherwise.

Definition at line 392 of file dynamixel_interface_driver.cpp.

◆ getModelNumber()

bool dynamixel_interface::DynamixelInterfaceDriver::getModelNumber ( int  servo_id,
uint16_t *  model_number 
) const

Retrieves the model number from the dynamixel's eeprom

Parameters
[in]servo_idThe ID of the servo to retrieve from
[out]model_numberStores the model_number returned
Returns
True on comm success, false otherwise.

Definition at line 318 of file dynamixel_interface_driver.cpp.

◆ getModelSpec()

const DynamixelSpec* dynamixel_interface::DynamixelInterfaceDriver::getModelSpec ( uint  model_number) const
inline

Get pointer to model spec data for given model number.

Definition at line 171 of file dynamixel_interface_driver.h.

◆ getSeriesName()

std::string dynamixel_interface::DynamixelInterfaceDriver::getSeriesName ( DynamixelSeriesType  type) const
inline

Returns a string version of the dynamixel series based on the input type

Parameters
[in]typethe type of the servo to read from
Returns
The string name of the Dynamixel series

Definition at line 435 of file dynamixel_interface_driver.h.

◆ getTargetTorque()

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.

Parameters
[in]servo_idThe ID of the servo to retrieve from
[in]typethe type of the servo to read from
[out]target_velocityStores the value returned
Returns
True on comm success, false otherwise.

Definition at line 493 of file dynamixel_interface_driver.cpp.

◆ getTorqueEnabled()

bool dynamixel_interface::DynamixelInterfaceDriver::getTorqueEnabled ( int  servo_id,
DynamixelSeriesType  type,
bool *  torque_enabled 
) const

Retrieves the torque enabled value from the dynamixel's ram.

Parameters
[in]servo_idThe ID of the servo to retrieve from
[in]typethe type of the servo to read from
[out]torque_enabledStores the status of torque enable
Returns
True on comm success, false otherwise.

Definition at line 442 of file dynamixel_interface_driver.cpp.

◆ initialise()

bool dynamixel_interface::DynamixelInterfaceDriver::initialise ( void  )

Parses Motor Data, Opens port and sets up driver

Returns
true if initialisation successful, false otherwise

Definition at line 259 of file dynamixel_interface_driver.cpp.

◆ loadMotorData()

bool dynamixel_interface::DynamixelInterfaceDriver::loadMotorData ( void  )
private

Loads in the motor specifications from the motor_data.yaml file

Returns
true if load successful, false otherwise

Definition at line 153 of file dynamixel_interface_driver.cpp.

◆ ping()

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

Parameters
[in]servo_idThe ID to ping on the bus.
Returns
True if a dynamixel responds, false otherwise.

Definition at line 295 of file dynamixel_interface_driver.cpp.

◆ readRegisters()

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.

Parameters
[in]servo_idThe ID of the servo to retrieve from
[in]addressThe address value in the control table the dynamixel will start reading from
[in]lengthThe number of bytes to read consecutively from the control table
[out]responseArray to store the raw dynamixel response.

Definition at line 544 of file dynamixel_interface_driver.cpp.

◆ setAngleLimits()

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

Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]min_anglethe minimum angle limit (in encoder values)
[in]max_anglethe maximum angle limit (in encoder values)
Returns
True on comm success, false otherwise.

Definition at line 1279 of file dynamixel_interface_driver.cpp.

◆ setMaxAngleLimit()

bool dynamixel_interface::DynamixelInterfaceDriver::setMaxAngleLimit ( int  servo_id,
DynamixelSeriesType  type,
int32_t  angle 
) const

Sets the maximum angle limit for the dynamixel

Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]angleThe maximum angle limit (in encoder values)
Returns
True on comm success, false otherwise.

Definition at line 1346 of file dynamixel_interface_driver.cpp.

◆ setMaxTorque()

bool dynamixel_interface::DynamixelInterfaceDriver::setMaxTorque ( int  servo_id,
DynamixelSeriesType  type,
uint16_t  max_torque 
) const

Sets the maximum torque limit for the dynamixel

Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]max_torquethe maximum torque limit
Returns
True on comm success, false otherwise.

Definition at line 1395 of file dynamixel_interface_driver.cpp.

◆ setMaxVelocity()

bool dynamixel_interface::DynamixelInterfaceDriver::setMaxVelocity ( int  servo_id,
DynamixelSeriesType  type,
uint32_t  max_vel 
) const

Sets the maximum velocity limit for the dynamixel

Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]max_velthe maximum velocity limit
Returns
True on comm success, false otherwise.

Definition at line 1450 of file dynamixel_interface_driver.cpp.

◆ setMinAngleLimit()

bool dynamixel_interface::DynamixelInterfaceDriver::setMinAngleLimit ( int  servo_id,
DynamixelSeriesType  type,
int32_t  angle 
) const

Sets the minimum angle limit for the dynamixel

Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]angleThe minimum angle limit (in encoder values)
Returns
True on comm success, false otherwise.

Definition at line 1297 of file dynamixel_interface_driver.cpp.

◆ setMultiPosition()

bool dynamixel_interface::DynamixelInterfaceDriver::setMultiPosition ( std::unordered_map< int, SyncData > &  position_data) const

Set many dynamixels with new position values in one instruction.

See also
syncWrite.
Parameters
[in]position_datamap of ids to syncdata objects containing position data
Returns
True on comm success, false otherwise.

Definition at line 2070 of file dynamixel_interface_driver.cpp.

◆ setMultiProfileVelocity()

bool dynamixel_interface::DynamixelInterfaceDriver::setMultiProfileVelocity ( std::unordered_map< int, SyncData > &  velocity_data) const

Set many dynamixels with new profile velocity values in one instruction.

See also
syncWrite.
Parameters
[in]velocity_datamap of ids to syncdata objects containing profile velocity data
Returns
True on comm success, false otherwise.

Definition at line 2137 of file dynamixel_interface_driver.cpp.

◆ setMultiTorque()

bool dynamixel_interface::DynamixelInterfaceDriver::setMultiTorque ( std::unordered_map< int, SyncData > &  torque_data) const

Set many dynamixels with new torque values in one instruction.

See also
syncWrite.
Parameters
[in]torque_datamap of ids to syncdata objects containing torque data
Returns
True on comm success, false otherwise.

Definition at line 2170 of file dynamixel_interface_driver.cpp.

◆ setMultiVelocity()

bool dynamixel_interface::DynamixelInterfaceDriver::setMultiVelocity ( std::unordered_map< int, SyncData > &  velocity_data) const

Set many dynamixels with new position values in one instruction.

See also
syncWrite.
Parameters
[in]velocity_datamap of ids to syncdata objects containing velocity data
Returns
True on comm success, false otherwise.

Definition at line 2104 of file dynamixel_interface_driver.cpp.

◆ setOperatingMode()

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.

Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]operating_modeThe method of control
Returns
True on comm success and valid operating mode, false otherwise.

Definition at line 1185 of file dynamixel_interface_driver.cpp.

◆ setPositionDerivativeGain()

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.

See also
setPIDGains
Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]gainThe derivative gain value to write
Returns
True on comm success, false otherwise.

Definition at line 1751 of file dynamixel_interface_driver.cpp.

◆ setPositionIntegralGain()

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.

See also
setPIDGains
Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]gainThe integral gain value to write
Returns
True on comm success, false otherwise.

Definition at line 1702 of file dynamixel_interface_driver.cpp.

◆ setPositionPIDGains()

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:

  • AX Series:
    • None
  • RX Series:
    • None
  • MX (1.0) Series:
    • Position: P,I,D
    • Velocity: None
    • Torque: None
  • XM Series:
    • Position: P,I,D
    • Velocity: P,I
    • Torque: None
  • Pro Series:
    • Position: P
    • Velocity: P,I
    • Torque: None -Sets the position PID values for the dynamixels
      Parameters
      [in]servo_idThe ID of the servo to write to
      [in]typethe type of the servo to read from
      [in]p_gainThe proportional gain value to write
      [in]i_gainThe integral gain value to write
      [in]d_gainThe derivative gain value to write
      Returns
      True on comm success, false otherwise.
      Sets the position PID values for the dynamixels
      Parameters
      [in]servo_idThe ID of the servo to write to
      [in]typethe type of the servo to read from
      [in]p_gainThe proportional gain value to write
      [in]i_gainThe integral gain value to write
      [in]d_gainThe derivative gain value to write
      Returns
      True on comm success, false otherwise.

Definition at line 1585 of file dynamixel_interface_driver.cpp.

◆ setPositionProportionalGain()

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.

See also
setPIDGains
Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]gainThe proportional gain value to write
Returns
True on comm success, false otherwise.

Definition at line 1651 of file dynamixel_interface_driver.cpp.

◆ setProfileVelocity()

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.

Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]velocityThe profile velocity value to write
Returns
True on comm success, false otherwise.

Definition at line 1944 of file dynamixel_interface_driver.cpp.

◆ setTorque()

bool dynamixel_interface::DynamixelInterfaceDriver::setTorque ( int  servo_id,
DynamixelSeriesType  type,
int16_t  torque 
) const

Sets the torque value of the dynamixel.

Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]torqueThe torque value to write
Returns
True on comm success, false otherwise.

Definition at line 1994 of file dynamixel_interface_driver.cpp.

◆ setTorqueControlEnabled()

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.

Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]onThe torque control state of the servo (true = on, false = off).
Returns
True on comm success, false otherwise.

Definition at line 1549 of file dynamixel_interface_driver.cpp.

◆ setTorqueEnabled()

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.

Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]onThe state of the servo (true = on, false = off).
Returns
True on comm success, false otherwise.

Definition at line 1498 of file dynamixel_interface_driver.cpp.

◆ setVelocityIntegralGain()

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.

See also
setPIDGains
Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]gainThe integral gain value to write
Returns
True on comm success, false otherwise.

Definition at line 1898 of file dynamixel_interface_driver.cpp.

◆ setVelocityPIDGains()

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

Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]p_gainThe proportional gain value to write
[in]i_gainThe integral gain value to write
[in]d_gainThe derivative gain value to write
Returns
True on comm success, false otherwise.

Definition at line 1802 of file dynamixel_interface_driver.cpp.

◆ setVelocityProportionalGain()

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.

See also
setPIDGains
Parameters
[in]servo_idThe ID of the servo to write to
[in]typethe type of the servo to read from
[in]gainThe proportional gain value to write
Returns
True on comm success, false otherwise.

Definition at line 1852 of file dynamixel_interface_driver.cpp.

◆ syncRead()

bool dynamixel_interface::DynamixelInterfaceDriver::syncRead ( std::unordered_map< int, SyncData *> &  read_data,
uint16_t  address,
uint16_t  length 
) const
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.

Parameters
[in]read_dataPointer to a map of SyncData objects, containing ids and vectors to read into
[in]addressThe address value in the control table the dynamixels will start reading from
[in]lengthThe number of bytes to read consecutively from the control table
Returns
true if at least one dynamixel was successfully read

Definition at line 1111 of file dynamixel_interface_driver.cpp.

◆ syncWrite()

bool dynamixel_interface::DynamixelInterfaceDriver::syncWrite ( std::unordered_map< int, SyncData > &  write_data,
uint16_t  address,
uint16_t  length 
) const
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.

Parameters
[in]write_dataPointer to a map of SyncData objects, containing ids and vectors to write from.
[in]addressThe address value in the control table the dynamixels will write to
[in]lengthThe number of bytes to write
Returns
true on successful write, false otherwise

Definition at line 2211 of file dynamixel_interface_driver.cpp.

◆ writeRegisters()

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.

Parameters
[in]servo_idThe ID of the servo to write to
[in]addressThe address value in the control table the dynamixel will start writing to
[in]lengthThe number of bytes to write consecutively to the control table
[in]dataArray containing the value to be written.
Returns
True on comm success, false otherwise.

Definition at line 2046 of file dynamixel_interface_driver.cpp.

Member Data Documentation

◆ baud_rate_

int dynamixel_interface::DynamixelInterfaceDriver::baud_rate_
private

baud rate

Definition at line 510 of file dynamixel_interface_driver.h.

◆ device_

std::string dynamixel_interface::DynamixelInterfaceDriver::device_
private

name of device to open

Definition at line 509 of file dynamixel_interface_driver.h.

◆ initialised_

bool dynamixel_interface::DynamixelInterfaceDriver::initialised_ = false
private

Variable to indicate if we're ready for comms.

Definition at line 516 of file dynamixel_interface_driver.h.

◆ model_specs_

std::unordered_map<uint16_t, const DynamixelSpec> dynamixel_interface::DynamixelInterfaceDriver::model_specs_
private

map of model numbers to motor specifications

Definition at line 519 of file dynamixel_interface_driver.h.

◆ packetHandler_

std::unique_ptr<dynamixel::PacketHandler> dynamixel_interface::DynamixelInterfaceDriver::packetHandler_
private

packet handler. Provides raw response deconstruction.

Definition at line 507 of file dynamixel_interface_driver.h.

◆ portHandler_

std::unique_ptr<dynamixel::PortHandler> dynamixel_interface::DynamixelInterfaceDriver::portHandler_
private

The port handler object. The dynamixel sdk serial object.

Definition at line 506 of file dynamixel_interface_driver.h.

◆ raw_read_map_

std::unordered_map<int, std::vector<uint8_t> > dynamixel_interface::DynamixelInterfaceDriver::raw_read_map_
private

map to store raw reads into

Definition at line 520 of file dynamixel_interface_driver.h.

◆ single_read_fallback_counter_

uint8_t dynamixel_interface::DynamixelInterfaceDriver::single_read_fallback_counter_
private

indicates group comm failure fallback interval

Definition at line 517 of file dynamixel_interface_driver.h.

◆ use_group_read_

bool dynamixel_interface::DynamixelInterfaceDriver::use_group_read_
private

using monolothic bulkRead or syncRead for bulk data exchange

Definition at line 513 of file dynamixel_interface_driver.h.

◆ use_group_write_

bool dynamixel_interface::DynamixelInterfaceDriver::use_group_write_
private

using monolothic syncWrite for bulk data exchange

Definition at line 514 of file dynamixel_interface_driver.h.

◆ use_legacy_protocol_

bool dynamixel_interface::DynamixelInterfaceDriver::use_legacy_protocol_
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.


The documentation for this class was generated from the following files:


dynamixel_interface
Author(s): Tom Molnar
autogenerated on Mon Feb 28 2022 22:15:51