dynamixel_interface_driver.h
Go to the documentation of this file.
1 /* CSIRO Open Source Software License Agreement (variation of the BSD / MIT License)
2  * Copyright (c) 2020, Commonwealth Scientific and Industrial Research Organisation (CSIRO) ABN 41 687 119 230.
3  * All rights reserved. CSIRO is willing to grant you a license to the dynamixel_actuator ROS packages on the following
4  * terms, except where otherwise indicated for third party material. Redistribution and use of this software in source
5  * and binary forms, with or without modification, are permitted provided that the following conditions are met:
6  * - Redistributions of source code must retain the above copyright notice, this list of conditions and the following
7  * disclaimer.
8  * - Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following
9  * disclaimer in the documentation and/or other materials provided with the distribution.
10  * - Neither the name of CSIRO nor the names of its contributors may be used to endorse or promote products derived from
11  * this software without specific prior written permission of CSIRO.
12  *
13  * EXCEPT AS EXPRESSLY STATED IN THIS AGREEMENT AND TO THE FULL EXTENT PERMITTED BY APPLICABLE LAW, THE SOFTWARE IS
14  * PROVIDED "AS-IS". CSIRO MAKES NO REPRESENTATIONS, WARRANTIES OR CONDITIONS OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING
15  * BUT NOT LIMITED TO ANY REPRESENTATIONS, WARRANTIES OR CONDITIONS REGARDING THE CONTENTS OR ACCURACY OF THE SOFTWARE,
16  * OR OF TITLE, MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, NON-INFRINGEMENT, THE ABSENCE OF LATENT OR OTHER
17  * DEFECTS, OR THE PRESENCE OR ABSENCE OF ERRORS, WHETHER OR NOT DISCOVERABLE.
18  * TO THE FULL EXTENT PERMITTED BY APPLICABLE LAW, IN NO EVENT SHALL CSIRO BE LIABLE ON ANY LEGAL THEORY (INCLUDING,
19  * WITHOUT LIMITATION, IN AN ACTION FOR BREACH OF CONTRACT, NEGLIGENCE OR OTHERWISE) FOR ANY CLAIM, LOSS, DAMAGES OR
20  * OTHER LIABILITY HOWSOEVER INCURRED. WITHOUT LIMITING THE SCOPE OF THE PREVIOUS SENTENCE THE EXCLUSION OF LIABILITY
21  * SHALL INCLUDE: LOSS OF PRODUCTION OR OPERATION TIME, LOSS, DAMAGE OR CORRUPTION OF DATA OR RECORDS; OR LOSS OF
22  * ANTICIPATED SAVINGS, OPPORTUNITY, REVENUE, PROFIT OR GOODWILL, OR OTHER ECONOMIC LOSS; OR ANY SPECIAL, INCIDENTAL,
23  * INDIRECT, CONSEQUENTIAL, PUNITIVE OR EXEMPLARY DAMAGES, ARISING OUT OF OR IN CONNECTION WITH THIS AGREEMENT, ACCESS
24  * OF THE SOFTWARE OR ANY OTHER DEALINGS WITH THE SOFTWARE, EVEN IF CSIRO HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH
25  * CLAIM, LOSS, DAMAGES OR OTHER LIABILITY. APPLICABLE LEGISLATION SUCH AS THE AUSTRALIAN CONSUMER LAW MAY APPLY
26  * REPRESENTATIONS, WARRANTIES, OR CONDITIONS, OR IMPOSES OBLIGATIONS OR LIABILITY ON CSIRO THAT CANNOT BE EXCLUDED,
27  * RESTRICTED OR MODIFIED TO THE FULL EXTENT SET OUT IN THE EXPRESS TERMS OF THIS CLAUSE ABOVE "CONSUMER GUARANTEES".
28  * TO THE EXTENT THAT SUCH CONSUMER GUARANTEES CONTINUE TO APPLY, THEN TO THE FULL EXTENT PERMITTED BY THE APPLICABLE
29  * LEGISLATION, THE LIABILITY OF CSIRO UNDER THE RELEVANT CONSUMER GUARANTEE IS LIMITED (WHERE PERMITTED AT CSIRO'S
30  * OPTION) TO ONE OF FOLLOWING REMEDIES OR SUBSTANTIALLY EQUIVALENT REMEDIES:
31  * (a) THE REPLACEMENT OF THE SOFTWARE, THE SUPPLY OF EQUIVALENT SOFTWARE, OR SUPPLYING RELEVANT SERVICES AGAIN;
32  * (b) THE REPAIR OF THE SOFTWARE;
33  * (c) THE PAYMENT OF THE COST OF REPLACING THE SOFTWARE, OF ACQUIRING EQUIVALENT SOFTWARE, HAVING THE RELEVANT
34  * SERVICES SUPPLIED AGAIN, OR HAVING THE SOFTWARE REPAIRED.
35  * IN THIS CLAUSE, CSIRO INCLUDES ANY THIRD PARTY AUTHOR OR OWNER OF ANY PART OF THE SOFTWARE OR MATERIAL DISTRIBUTED
36  * WITH IT. CSIRO MAY ENFORCE ANY RIGHTS ON BEHALF OF THE RELEVANT THIRD PARTY.
37  *
38  * Third Party Components:
39  *
40  * The following third party components are distributed with the Software. You agree to comply with the license terms
41  * for these components as part of accessing the Software. Other third party software may also be identified in
42  * separate files distributed with the Software.
43  * ___________________________________________________________________
44  *
45  * dynamixel_interface is forked from projects authored by Brian
46  * Axelrod (on behalf of Willow Garage):
47  *
48  * https://github.com/baxelrod/dynamixel_pro_controller
49  * https://github.com/baxelrod/dynamixel_pro_driver
50  *
51  * Thus they retain the following notice:
52  *
53  * Software License Agreement (BSD License)
54  * Copyright (c) 2013, Willow Garage
55  * All rights reserved.
56  * Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
57  * following conditions are met:
58  * - Redistributions of source code must retain the above copyright notice, this list of conditions and the following
59  * disclaimer.
60  * - Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
61  * following disclaimer in the documentation and/or other materials provided with the distribution.
62  * - Neither the name of Willow Garage nor the names of its contributors may be used to endorse or promote products
63  * derived from this software without specific prior written permission.
64  *
65  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
66  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
67  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
68  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
69  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
70  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
71  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
72  * ___________________________________________________________________
73  */
74 
83 #ifndef DYNAMIXEL_INTERFACE_DRIVER_H_
84 #define DYNAMIXEL_INTERFACE_DRIVER_H_
85 
86 #include <stdint.h>
87 #include <map>
88 #include <string>
89 #include <unordered_map>
90 #include <vector>
91 
94 #include <ros/ros.h>
95 
96 namespace dynamixel_interface
97 {
100 {
101  std::string name;
102  uint16_t model_number;
108  double effort_reg_max;
110 };
111 
112 
114 struct SyncData
115 {
116  int id;
118  bool success;
119  uint8_t error;
120  std::vector<uint8_t> data;
121 };
122 
125 {
126  int32_t position;
127  int32_t velocity;
128  int32_t effort;
129 };
130 
133 {
134  int32_t voltage;
135  int32_t temperature;
136 };
137 
140 {
141  std::array<uint16_t, 4> port_values;
142 };
143 
147 {
148 public:
155  DynamixelInterfaceDriver(const std::string &device = "/dev/ttyUSB0", int baud = 1000000,
156  bool use_legacy_protocol = false, bool use_group_read = true, bool use_group_write = true);
157 
160 
163  bool initialise(void);
164 
168  bool ping(int servo_id) const;
169 
171  inline const DynamixelSpec *getModelSpec(uint model_number) const
172  {
173  auto it = model_specs_.find(model_number);
174  if (it != model_specs_.end())
175  {
176  return &(it->second);
177  }
178  else
179  {
180  return nullptr;
181  }
182  };
183 
184  // ************************************ GETTERS ***************************************** //
185 
190  bool getModelNumber(int servo_id, uint16_t *model_number) const;
191 
197  bool getErrorStatus(int servo_id, DynamixelSeriesType type, uint8_t *error) const;
198 
204  bool getMaxTorque(int servo_id, DynamixelSeriesType type, uint16_t *max_torque) const;
205 
211  bool getTorqueEnabled(int servo_id, DynamixelSeriesType type, bool *torque_enabled) const;
212 
218  bool getTargetTorque(int servo_id, DynamixelSeriesType type, int16_t *target_torque) const;
219 
226  bool readRegisters(int servo_id, uint16_t address, uint16_t length, std::vector<uint8_t> *response) const;
227 
228  // *********************** BULK_READ METHODS *************************** //
229 
236  bool getBulkState(std::unordered_map<int, DynamixelState> &state_map) const;
237 
241  bool getBulkDataportInfo(std::unordered_map<int, DynamixelDataport> &data_map) const;
242 
246  bool getBulkDiagnosticInfo(std::unordered_map<int, DynamixelDiagnostic> &diag_map) const;
247 
248  // **************************** SETTERS ******************************** //
249 
259  bool setOperatingMode(int servo_id, DynamixelSeriesType type, DynamixelControlMode operating_mode) const;
260 
267  bool setAngleLimits(int servo_id, DynamixelSeriesType type, int32_t min_angle, int32_t max_angle) const;
268 
274  bool setMinAngleLimit(int servo_id, DynamixelSeriesType type, int32_t angle) const;
275 
281  bool setMaxAngleLimit(int servo_id, DynamixelSeriesType type, int32_t angle) const;
282 
288  bool setMaxTorque(int servo_id, DynamixelSeriesType type, uint16_t max_torque) const;
289 
295  bool setMaxVelocity(int servo_id, DynamixelSeriesType type, uint32_t max_vel) const;
296 
302  bool setTorqueEnabled(int servo_id, DynamixelSeriesType type, bool on) const;
303 
310  bool setTorqueControlEnabled(int servo_id, DynamixelSeriesType type, bool on) const;
311 
333 
341  bool setPositionPIDGains(int servo_id, DynamixelSeriesType type, double p_gain, double i_gain, double d_gain) const;
342 
348  bool setPositionProportionalGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const;
349 
355  bool setPositionIntegralGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const;
356 
362  bool setPositionDerivativeGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const;
363 
371  bool setVelocityPIDGains(int servo_id, DynamixelSeriesType type, double p_gain, double i_gain) const;
372 
378  bool setVelocityProportionalGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const;
379 
385  bool setVelocityIntegralGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const;
386 
392  bool setProfileVelocity(int servo_id, DynamixelSeriesType type, int32_t velocity) const;
393 
399  bool setTorque(int servo_id, DynamixelSeriesType type, int16_t torque) const;
400 
408  bool writeRegisters(int servo_id, uint16_t address, uint16_t length, uint8_t *data) const;
409 
410  // *********************** SYNC_WRITE METHODS *************************** //
411 
415  bool setMultiPosition(std::unordered_map<int, SyncData> &position_data) const;
416 
420  bool setMultiVelocity(std::unordered_map<int, SyncData> &velocity_data) const;
421 
425  bool setMultiProfileVelocity(std::unordered_map<int, SyncData> &velocity_data) const;
426 
430  bool setMultiTorque(std::unordered_map<int, SyncData> &torque_data) const;
431 
435  inline std::string getSeriesName(DynamixelSeriesType type) const
436  {
437  std::string series_name = "undefined";
438  switch (type)
439  {
440  case kSeriesAX:
441  series_name = "AX";
442  break;
443  case kSeriesRX:
444  series_name = "RX";
445  break;
446  case kSeriesDX:
447  series_name = "DX";
448  break;
449  case kSeriesEX:
450  series_name = "EX";
451  break;
452  case kSeriesLegacyMX:
453  series_name = "Legacy MX";
454  break;
455  case kSeriesMX:
456  series_name = "MX";
457  break;
458  case kSeriesX:
459  series_name = "X";
460  break;
461  case kSeriesP:
462  series_name = "P";
463  break;
464  case kSeriesLegacyPro:
465  series_name = "Legacy Pro";
466  break;
467  }
468  return series_name;
469  };
470 
471 private:
474  bool loadMotorData(void);
475 
484  bool bulkRead(std::unordered_map<int, SyncData*> &read_data, uint16_t address, uint16_t length) const;
485 
493  bool syncRead(std::unordered_map<int, SyncData*> &read_data, uint16_t address, uint16_t length) const;
494 
503  bool syncWrite(std::unordered_map<int, SyncData> &write_data, uint16_t address, uint16_t length) const;
504 
505 private:
506  std::unique_ptr<dynamixel::PortHandler> portHandler_;
507  std::unique_ptr<dynamixel::PacketHandler> packetHandler_;
508 
509  std::string device_;
511 
515 
516  bool initialised_ = false;
518 
519  std::unordered_map<uint16_t, const DynamixelSpec> model_specs_;
520  std::unordered_map<int, std::vector<uint8_t>> raw_read_map_;
521 };
522 
523 } // namespace dynamixel_interface
524 
525 #endif // DYNAMIXEL_INTERFACE_DRIVER_H_
dynamixel_interface::DynamixelInterfaceDriver::setPositionProportionalGain
bool setPositionProportionalGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const
Definition: dynamixel_interface_driver.cpp:1651
dynamixel_interface::DynamixelInterfaceDriver::setMultiPosition
bool setMultiPosition(std::unordered_map< int, SyncData > &position_data) const
Definition: dynamixel_interface_driver.cpp:2070
dynamixel_interface::DynamixelInterfaceDriver::setVelocityProportionalGain
bool setVelocityProportionalGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const
Definition: dynamixel_interface_driver.cpp:1852
dynamixel_interface::DynamixelInterfaceDriver::setMinAngleLimit
bool setMinAngleLimit(int servo_id, DynamixelSeriesType type, int32_t angle) const
Definition: dynamixel_interface_driver.cpp:1297
dynamixel_interface::DynamixelInterfaceDriver::setMaxTorque
bool setMaxTorque(int servo_id, DynamixelSeriesType type, uint16_t max_torque) const
Definition: dynamixel_interface_driver.cpp:1395
dynamixel_interface::DynamixelInterfaceDriver::setPositionPIDGains
bool setPositionPIDGains(int servo_id, DynamixelSeriesType type, double p_gain, double i_gain, double d_gain) const
Definition: dynamixel_interface_driver.cpp:1585
dynamixel_interface::DynamixelInterfaceDriver::getModelNumber
bool getModelNumber(int servo_id, uint16_t *model_number) const
Definition: dynamixel_interface_driver.cpp:318
dynamixel_interface::DynamixelSpec::effort_reg_to_mA
double effort_reg_to_mA
Conversion factor from register values to current in mA.
Definition: dynamixel_interface_driver.h:109
dynamixel_interface::DynamixelInterfaceDriver::baud_rate_
int baud_rate_
baud rate
Definition: dynamixel_interface_driver.h:510
dynamixel_interface::DynamixelSeriesType
DynamixelSeriesType
Dynamixel types.
Definition: dynamixel_const.h:95
dynamixel_interface::DynamixelInterfaceDriver::readRegisters
bool readRegisters(int servo_id, uint16_t address, uint16_t length, std::vector< uint8_t > *response) const
Definition: dynamixel_interface_driver.cpp:544
dynamixel_interface::DynamixelInterfaceDriver::use_group_write_
bool use_group_write_
using monolothic syncWrite for bulk data exchange
Definition: dynamixel_interface_driver.h:514
dynamixel_interface::DynamixelInterfaceDriver::bulkRead
bool bulkRead(std::unordered_map< int, SyncData * > &read_data, uint16_t address, uint16_t length) const
Definition: dynamixel_interface_driver.cpp:1049
ros.h
dynamixel_interface::DynamixelInterfaceDriver::model_specs_
std::unordered_map< uint16_t, const DynamixelSpec > model_specs_
map of model numbers to motor specifications
Definition: dynamixel_interface_driver.h:519
dynamixel_interface::SyncData::success
bool success
bool indicating comms success
Definition: dynamixel_interface_driver.h:118
dynamixel_interface::DynamixelSpec::model_number
uint16_t model_number
Model number (e.g 29 = MX-28)
Definition: dynamixel_interface_driver.h:102
dynamixel_interface::kSeriesAX
@ kSeriesAX
Definition: dynamixel_const.h:97
dynamixel_interface::DynamixelInterfaceDriver::getTorqueEnabled
bool getTorqueEnabled(int servo_id, DynamixelSeriesType type, bool *torque_enabled) const
Definition: dynamixel_interface_driver.cpp:442
dynamixel_interface::DynamixelInterfaceDriver::packetHandler_
std::unique_ptr< dynamixel::PacketHandler > packetHandler_
packet handler. Provides raw response deconstruction.
Definition: dynamixel_interface_driver.h:507
dynamixel_interface::DynamixelInterfaceDriver::device_
std::string device_
name of device to open
Definition: dynamixel_interface_driver.h:509
dynamixel_interface::DynamixelInterfaceDriver::setVelocityIntegralGain
bool setVelocityIntegralGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const
Definition: dynamixel_interface_driver.cpp:1898
dynamixel_interface::DynamixelInterfaceDriver::initialised_
bool initialised_
Variable to indicate if we're ready for comms.
Definition: dynamixel_interface_driver.h:516
dynamixel_interface::DynamixelInterfaceDriver::setTorqueEnabled
bool setTorqueEnabled(int servo_id, DynamixelSeriesType type, bool on) const
Definition: dynamixel_interface_driver.cpp:1498
dynamixel_interface::DynamixelInterfaceDriver::setOperatingMode
bool setOperatingMode(int servo_id, DynamixelSeriesType type, DynamixelControlMode operating_mode) const
Definition: dynamixel_interface_driver.cpp:1185
dynamixel_interface::SyncData::id
int id
id of dynamixel
Definition: dynamixel_interface_driver.h:116
dynamixel_interface::DynamixelInterfaceDriver::writeRegisters
bool writeRegisters(int servo_id, uint16_t address, uint16_t length, uint8_t *data) const
Definition: dynamixel_interface_driver.cpp:2046
dynamixel_interface::DynamixelInterfaceDriver::syncRead
bool syncRead(std::unordered_map< int, SyncData * > &read_data, uint16_t address, uint16_t length) const
Definition: dynamixel_interface_driver.cpp:1111
dynamixel_interface::kSeriesMX
@ kSeriesMX
Definition: dynamixel_const.h:102
dynamixel_interface::DynamixelInterfaceDriver::setPositionIntegralGain
bool setPositionIntegralGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const
Definition: dynamixel_interface_driver.cpp:1702
dynamixel_interface::SyncData
Basic struct for representing dynamixel data exchange.
Definition: dynamixel_interface_driver.h:114
dynamixel_interface::kSeriesRX
@ kSeriesRX
Definition: dynamixel_const.h:98
dynamixel_interface::DynamixelDataport::port_values
std::array< uint16_t, 4 > port_values
values from dataports, units differ by series and dataport setting
Definition: dynamixel_interface_driver.h:141
dynamixel_interface::DynamixelInterfaceDriver
Definition: dynamixel_interface_driver.h:146
dynamixel_interface::DynamixelInterfaceDriver::getBulkDiagnosticInfo
bool getBulkDiagnosticInfo(std::unordered_map< int, DynamixelDiagnostic > &diag_map) const
Definition: dynamixel_interface_driver.cpp:876
dynamixel_interface::DynamixelInterfaceDriver::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)
Definition: dynamixel_interface_driver.cpp:95
dynamixel_interface::DynamixelState::position
int32_t position
position register value, units differ by series
Definition: dynamixel_interface_driver.h:126
dynamixel_interface::DynamixelDataport
data struct used with getBulkDataportInfo() to retrieve dataport values
Definition: dynamixel_interface_driver.h:139
dynamixel_interface::kSeriesEX
@ kSeriesEX
Definition: dynamixel_const.h:100
dynamixel_interface::DynamixelInterfaceDriver::setPositionDerivativeGain
bool setPositionDerivativeGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const
Definition: dynamixel_interface_driver.cpp:1751
dynamixel_interface::DynamixelInterfaceDriver::~DynamixelInterfaceDriver
~DynamixelInterfaceDriver()
Destructor. Closes and releases serial port.
Definition: dynamixel_interface_driver.cpp:143
dynamixel_interface::DynamixelState
data struct used with getBulkState() to retrieve physical state
Definition: dynamixel_interface_driver.h:124
dynamixel_const.h
Defines the register address tables for each series of dynamixel, as well as the control and status c...
dynamixel_interface::DynamixelInterfaceDriver::use_legacy_protocol_
bool use_legacy_protocol_
if we are using legacy 1.0 protocol or newer 2.0 protocol (depends on model support)
Definition: dynamixel_interface_driver.h:512
dynamixel_interface::DynamixelSpec
Struct that describes the dynamixel motor's static and physical properties.
Definition: dynamixel_interface_driver.h:99
dynamixel_interface::DynamixelInterfaceDriver::getBulkState
bool getBulkState(std::unordered_map< int, DynamixelState > &state_map) const
Definition: dynamixel_interface_driver.cpp:574
dynamixel_interface::DynamixelInterfaceDriver::setVelocityPIDGains
bool setVelocityPIDGains(int servo_id, DynamixelSeriesType type, double p_gain, double i_gain) const
Definition: dynamixel_interface_driver.cpp:1802
dynamixel_interface::DynamixelDiagnostic
data struct used with getBulkDiagnosticInfo() to retrieve diagnostics
Definition: dynamixel_interface_driver.h:132
dynamixel_interface::DynamixelInterfaceDriver::getErrorStatus
bool getErrorStatus(int servo_id, DynamixelSeriesType type, uint8_t *error) const
Definition: dynamixel_interface_driver.cpp:342
dynamixel_interface::DynamixelInterfaceDriver::setTorque
bool setTorque(int servo_id, DynamixelSeriesType type, int16_t torque) const
Definition: dynamixel_interface_driver.cpp:1994
dynamixel_interface::DynamixelInterfaceDriver::getTargetTorque
bool getTargetTorque(int servo_id, DynamixelSeriesType type, int16_t *target_torque) const
Definition: dynamixel_interface_driver.cpp:493
dynamixel_interface::DynamixelControlMode
DynamixelControlMode
Definition: dynamixel_const.h:368
dynamixel_interface::DynamixelSpec::name
std::string name
The Model Name.
Definition: dynamixel_interface_driver.h:101
dynamixel_interface::SyncData::type
DynamixelSeriesType type
type of dynamixel
Definition: dynamixel_interface_driver.h:117
dynamixel_interface::kSeriesDX
@ kSeriesDX
Definition: dynamixel_const.h:99
dynamixel_interface::DynamixelInterfaceDriver::setMultiProfileVelocity
bool setMultiProfileVelocity(std::unordered_map< int, SyncData > &velocity_data) const
Definition: dynamixel_interface_driver.cpp:2137
dynamixel_interface::DynamixelSpec::effort_reg_max
double effort_reg_max
Max possible value for effort register.
Definition: dynamixel_interface_driver.h:108
dynamixel_interface::DynamixelInterfaceDriver::loadMotorData
bool loadMotorData(void)
Definition: dynamixel_interface_driver.cpp:153
dynamixel_interface::kSeriesX
@ kSeriesX
Definition: dynamixel_const.h:103
dynamixel_interface::DynamixelInterfaceDriver::setTorqueControlEnabled
bool setTorqueControlEnabled(int servo_id, DynamixelSeriesType type, bool on) const
Definition: dynamixel_interface_driver.cpp:1549
dynamixel_interface::DynamixelInterfaceDriver::setMultiTorque
bool setMultiTorque(std::unordered_map< int, SyncData > &torque_data) const
Definition: dynamixel_interface_driver.cpp:2170
dynamixel_interface::DynamixelState::velocity
int32_t velocity
velocity register value, units differ by series
Definition: dynamixel_interface_driver.h:127
dynamixel_interface::SyncData::data
std::vector< uint8_t > data
IO data array.
Definition: dynamixel_interface_driver.h:120
dynamixel_interface::kSeriesLegacyMX
@ kSeriesLegacyMX
Definition: dynamixel_const.h:101
dynamixel_interface::DynamixelSpec::encoder_cpr
int encoder_cpr
Motor encoder counts per revolution.
Definition: dynamixel_interface_driver.h:105
dynamixel_interface::SyncData::error
uint8_t error
Error code.
Definition: dynamixel_interface_driver.h:119
dynamixel_interface::DynamixelDiagnostic::temperature
int32_t temperature
temperature register value, usually units of 0.1C
Definition: dynamixel_interface_driver.h:135
dynamixel_interface::DynamixelInterfaceDriver::ping
bool ping(int servo_id) const
Definition: dynamixel_interface_driver.cpp:295
dynamixel_interface::DynamixelInterfaceDriver::use_group_read_
bool use_group_read_
using monolothic bulkRead or syncRead for bulk data exchange
Definition: dynamixel_interface_driver.h:513
dynamixel_interface::DynamixelSpec::type
DynamixelSeriesType type
Model type (e.g MX, AX, Pro)
Definition: dynamixel_interface_driver.h:103
dynamixel_interface::DynamixelInterfaceDriver::portHandler_
std::unique_ptr< dynamixel::PortHandler > portHandler_
The port handler object. The dynamixel sdk serial object.
Definition: dynamixel_interface_driver.h:506
dynamixel_interface::DynamixelSpec::external_ports
bool external_ports
If this model has data ports.
Definition: dynamixel_interface_driver.h:104
dynamixel_interface::DynamixelState::effort
int32_t effort
effort register value, units differ by series
Definition: dynamixel_interface_driver.h:128
dynamixel_interface::DynamixelInterfaceDriver::single_read_fallback_counter_
uint8_t single_read_fallback_counter_
indicates group comm failure fallback interval
Definition: dynamixel_interface_driver.h:517
dynamixel_interface::DynamixelInterfaceDriver::setMultiVelocity
bool setMultiVelocity(std::unordered_map< int, SyncData > &velocity_data) const
Definition: dynamixel_interface_driver.cpp:2104
dynamixel_interface::kSeriesLegacyPro
@ kSeriesLegacyPro
Definition: dynamixel_const.h:104
dynamixel_interface::DynamixelInterfaceDriver::raw_read_map_
std::unordered_map< int, std::vector< uint8_t > > raw_read_map_
map to store raw reads into
Definition: dynamixel_interface_driver.h:520
dynamixel_sdk.h
dynamixel_interface::DynamixelSpec::encoder_range_deg
double encoder_range_deg
Motor encoder range in degrees.
Definition: dynamixel_interface_driver.h:106
dynamixel_interface::DynamixelInterfaceDriver::getModelSpec
const DynamixelSpec * getModelSpec(uint model_number) const
Get pointer to model spec data for given model number.
Definition: dynamixel_interface_driver.h:171
dynamixel_interface::DynamixelInterfaceDriver::getMaxTorque
bool getMaxTorque(int servo_id, DynamixelSeriesType type, uint16_t *max_torque) const
Definition: dynamixel_interface_driver.cpp:392
dynamixel_interface::DynamixelDiagnostic::voltage
int32_t voltage
voltage register value, usually units of 0.1V
Definition: dynamixel_interface_driver.h:134
dynamixel_interface::DynamixelInterfaceDriver::setAngleLimits
bool setAngleLimits(int servo_id, DynamixelSeriesType type, int32_t min_angle, int32_t max_angle) const
Definition: dynamixel_interface_driver.cpp:1279
dynamixel_interface::DynamixelInterfaceDriver::setProfileVelocity
bool setProfileVelocity(int servo_id, DynamixelSeriesType type, int32_t velocity) const
Definition: dynamixel_interface_driver.cpp:1944
dynamixel_interface
Definition: dynamixel_const.h:92
dynamixel_interface::kSeriesP
@ kSeriesP
Definition: dynamixel_const.h:105
dynamixel_interface::DynamixelInterfaceDriver::initialise
bool initialise(void)
Definition: dynamixel_interface_driver.cpp:259
dynamixel_interface::DynamixelInterfaceDriver::getBulkDataportInfo
bool getBulkDataportInfo(std::unordered_map< int, DynamixelDataport > &data_map) const
Definition: dynamixel_interface_driver.cpp:742
dynamixel_interface::DynamixelInterfaceDriver::setMaxAngleLimit
bool setMaxAngleLimit(int servo_id, DynamixelSeriesType type, int32_t angle) const
Definition: dynamixel_interface_driver.cpp:1346
dynamixel_interface::DynamixelInterfaceDriver::setMaxVelocity
bool setMaxVelocity(int servo_id, DynamixelSeriesType type, uint32_t max_vel) const
Definition: dynamixel_interface_driver.cpp:1450
dynamixel_interface::DynamixelInterfaceDriver::getSeriesName
std::string getSeriesName(DynamixelSeriesType type) const
Definition: dynamixel_interface_driver.h:435
dynamixel_interface::DynamixelSpec::velocity_radps_to_reg
double velocity_radps_to_reg
Conversion factor from velocity in radians/sec to register counts.
Definition: dynamixel_interface_driver.h:107
dynamixel_interface::DynamixelInterfaceDriver::syncWrite
bool syncWrite(std::unordered_map< int, SyncData > &write_data, uint16_t address, uint16_t length) const
Definition: dynamixel_interface_driver.cpp:2211


dynamixel_interface
Author(s): Tom Molnar
autogenerated on Wed Mar 2 2022 00:13:19