Go to the documentation of this file.
83 #ifndef DYNAMIXEL_INTERFACE_DRIVER_H_
84 #define DYNAMIXEL_INTERFACE_DRIVER_H_
89 #include <unordered_map>
156 bool use_legacy_protocol =
false,
bool use_group_read =
true,
bool use_group_write =
true);
168 bool ping(
int servo_id)
const;
176 return &(it->second);
226 bool readRegisters(
int servo_id, uint16_t address, uint16_t length, std::vector<uint8_t> *response)
const;
236 bool getBulkState(std::unordered_map<int, DynamixelState> &state_map)
const;
408 bool writeRegisters(
int servo_id, uint16_t address, uint16_t length, uint8_t *data)
const;
415 bool setMultiPosition(std::unordered_map<int, SyncData> &position_data)
const;
420 bool setMultiVelocity(std::unordered_map<int, SyncData> &velocity_data)
const;
430 bool setMultiTorque(std::unordered_map<int, SyncData> &torque_data)
const;
437 std::string series_name =
"undefined";
453 series_name =
"Legacy MX";
465 series_name =
"Legacy Pro";
484 bool bulkRead(std::unordered_map<int, SyncData*> &read_data, uint16_t address, uint16_t length)
const;
493 bool syncRead(std::unordered_map<int, SyncData*> &read_data, uint16_t address, uint16_t length)
const;
503 bool syncWrite(std::unordered_map<int, SyncData> &write_data, uint16_t address, uint16_t length)
const;
525 #endif // DYNAMIXEL_INTERFACE_DRIVER_H_
bool setPositionProportionalGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const
bool setMultiPosition(std::unordered_map< int, SyncData > &position_data) const
bool setVelocityProportionalGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const
bool setMinAngleLimit(int servo_id, DynamixelSeriesType type, int32_t angle) const
bool setMaxTorque(int servo_id, DynamixelSeriesType type, uint16_t max_torque) const
bool setPositionPIDGains(int servo_id, DynamixelSeriesType type, double p_gain, double i_gain, double d_gain) const
bool getModelNumber(int servo_id, uint16_t *model_number) const
double effort_reg_to_mA
Conversion factor from register values to current in mA.
DynamixelSeriesType
Dynamixel types.
bool readRegisters(int servo_id, uint16_t address, uint16_t length, std::vector< uint8_t > *response) const
bool use_group_write_
using monolothic syncWrite for bulk data exchange
bool bulkRead(std::unordered_map< int, SyncData * > &read_data, uint16_t address, uint16_t length) const
std::unordered_map< uint16_t, const DynamixelSpec > model_specs_
map of model numbers to motor specifications
bool success
bool indicating comms success
uint16_t model_number
Model number (e.g 29 = MX-28)
bool getTorqueEnabled(int servo_id, DynamixelSeriesType type, bool *torque_enabled) const
std::unique_ptr< dynamixel::PacketHandler > packetHandler_
packet handler. Provides raw response deconstruction.
std::string device_
name of device to open
bool setVelocityIntegralGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const
bool initialised_
Variable to indicate if we're ready for comms.
bool setTorqueEnabled(int servo_id, DynamixelSeriesType type, bool on) const
bool setOperatingMode(int servo_id, DynamixelSeriesType type, DynamixelControlMode operating_mode) const
bool writeRegisters(int servo_id, uint16_t address, uint16_t length, uint8_t *data) const
bool syncRead(std::unordered_map< int, SyncData * > &read_data, uint16_t address, uint16_t length) const
bool setPositionIntegralGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const
Basic struct for representing dynamixel data exchange.
std::array< uint16_t, 4 > port_values
values from dataports, units differ by series and dataport setting
bool getBulkDiagnosticInfo(std::unordered_map< int, DynamixelDiagnostic > &diag_map) const
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)
int32_t position
position register value, units differ by series
data struct used with getBulkDataportInfo() to retrieve dataport values
bool setPositionDerivativeGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const
~DynamixelInterfaceDriver()
Destructor. Closes and releases serial port.
data struct used with getBulkState() to retrieve physical state
Defines the register address tables for each series of dynamixel, as well as the control and status c...
bool use_legacy_protocol_
if we are using legacy 1.0 protocol or newer 2.0 protocol (depends on model support)
Struct that describes the dynamixel motor's static and physical properties.
bool getBulkState(std::unordered_map< int, DynamixelState > &state_map) const
bool setVelocityPIDGains(int servo_id, DynamixelSeriesType type, double p_gain, double i_gain) const
data struct used with getBulkDiagnosticInfo() to retrieve diagnostics
bool getErrorStatus(int servo_id, DynamixelSeriesType type, uint8_t *error) const
bool setTorque(int servo_id, DynamixelSeriesType type, int16_t torque) const
bool getTargetTorque(int servo_id, DynamixelSeriesType type, int16_t *target_torque) const
std::string name
The Model Name.
DynamixelSeriesType type
type of dynamixel
bool setMultiProfileVelocity(std::unordered_map< int, SyncData > &velocity_data) const
double effort_reg_max
Max possible value for effort register.
bool setTorqueControlEnabled(int servo_id, DynamixelSeriesType type, bool on) const
bool setMultiTorque(std::unordered_map< int, SyncData > &torque_data) const
int32_t velocity
velocity register value, units differ by series
std::vector< uint8_t > data
IO data array.
int encoder_cpr
Motor encoder counts per revolution.
int32_t temperature
temperature register value, usually units of 0.1C
bool ping(int servo_id) const
bool use_group_read_
using monolothic bulkRead or syncRead for bulk data exchange
DynamixelSeriesType type
Model type (e.g MX, AX, Pro)
std::unique_ptr< dynamixel::PortHandler > portHandler_
The port handler object. The dynamixel sdk serial object.
bool external_ports
If this model has data ports.
int32_t effort
effort register value, units differ by series
uint8_t single_read_fallback_counter_
indicates group comm failure fallback interval
bool setMultiVelocity(std::unordered_map< int, SyncData > &velocity_data) const
std::unordered_map< int, std::vector< uint8_t > > raw_read_map_
map to store raw reads into
double encoder_range_deg
Motor encoder range in degrees.
const DynamixelSpec * getModelSpec(uint model_number) const
Get pointer to model spec data for given model number.
bool getMaxTorque(int servo_id, DynamixelSeriesType type, uint16_t *max_torque) const
int32_t voltage
voltage register value, usually units of 0.1V
bool setAngleLimits(int servo_id, DynamixelSeriesType type, int32_t min_angle, int32_t max_angle) const
bool setProfileVelocity(int servo_id, DynamixelSeriesType type, int32_t velocity) const
bool getBulkDataportInfo(std::unordered_map< int, DynamixelDataport > &data_map) const
bool setMaxAngleLimit(int servo_id, DynamixelSeriesType type, int32_t angle) const
bool setMaxVelocity(int servo_id, DynamixelSeriesType type, uint32_t max_vel) const
std::string getSeriesName(DynamixelSeriesType type) const
double velocity_radps_to_reg
Conversion factor from velocity in radians/sec to register counts.
bool syncWrite(std::unordered_map< int, SyncData > &write_data, uint16_t address, uint16_t length) const