dynamixel_interface_driver.cpp
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 #include <ros/package.h>
84 #include "yaml-cpp/yaml.h"
85 
86 namespace dynamixel_interface
87 {
95 DynamixelInterfaceDriver::DynamixelInterfaceDriver(const std::string &device, int baud, bool use_legacy_protocol,
96  bool use_group_read, bool use_group_write)
97 {
98  ROS_INFO("Device is '%s' with baud rate '%d'", device.c_str(), baud);
99  if (use_legacy_protocol)
100  {
101  ROS_INFO("Using legacy protocol");
102  }
103  if (use_group_read)
104  {
105  ROS_INFO("Using group read methods");
106  }
107  if (use_group_write)
108  {
109  ROS_INFO("Using group write methods");
110  }
111 
112  // set device and baud rate
113  device_ = device;
114  baud_rate_ = baud;
115 
116  // set indicator for using group comms
117  use_legacy_protocol_ = use_legacy_protocol;
118  use_group_read_ = use_group_read;
119  use_group_write_ = use_group_write;
120 
121  // intialise failsafe fallback counter
123 
124  // Initialize PortHandler instance
125  // Set the port path
126  // Get methods and members of PortHandlerLinux
127  portHandler_ = std::unique_ptr<dynamixel::PortHandler>(dynamixel::PortHandler::getPortHandler(device.c_str()));
128 
129  // set packet handler for requested protocol version
131  {
132  // Initialize PacketHandler instances for each protocol version
133  packetHandler_ = std::unique_ptr<dynamixel::PacketHandler>(dynamixel::PacketHandler::getPacketHandler(1.0));
134  }
135  else
136  {
137  packetHandler_ = std::unique_ptr<dynamixel::PacketHandler>(dynamixel::PacketHandler::getPacketHandler(2.0));
138  }
139 
140 }
141 
144 {
145  if (initialised_)
146  {
147  portHandler_->closePort();
148  }
149 }
150 
154 {
155 
156  ROS_INFO("Initialising Dynamixel Port Driver");
157 
158  // read in motor data yaml file
159  // load the file containing model info, we're not using the param server here
160  std::string path = ros::package::getPath("dynamixel_interface");
161  path += "/config/motor_data.yaml";
162  YAML::Node doc;
163  ROS_INFO("Loading motor data from file");
164  try
165  {
166  doc = YAML::LoadFile(path);
167  }
168  catch (const YAML::BadFile &exception)
169  {
170  ROS_ERROR("Unable to load motor_data.yaml file, expected at %s", path.c_str());
171  return false;
172  ;
173  }
174 
175  // read in the dynamixel model information from the motor data file
176  for (int i = 0; i < doc.size(); i++)
177  {
178  DynamixelSpec spec;
179 
180  // Load the basic specs of this motor type
181  spec.name = doc[i]["name"].as<std::string>();
182  spec.model_number = doc[i]["model_number"].as<uint>();
183 
184  std::string type = doc[i]["series"].as<std::string>();
185  if (type == "M")
186  {
187  spec.type = kSeriesMX;
188  }
189  else if (type == "LM")
190  {
191  spec.type = kSeriesLegacyMX;
192  }
193  else if (type == "X")
194  {
195  spec.type = kSeriesX;
196  }
197  else if (type == "A")
198  {
199  spec.type = kSeriesAX;
200  }
201  else if (type == "R")
202  {
203  spec.type = kSeriesRX;
204  }
205  else if (type == "D")
206  {
207  spec.type = kSeriesDX;
208  }
209  else if (type == "E")
210  {
211  spec.type = kSeriesEX;
212  }
213  else if (type == "P")
214  {
215  spec.type = kSeriesP;
216  }
217  else if (type == "LP")
218  {
219  spec.type = kSeriesLegacyPro;
220  }
221  else
222  {
223  spec.type = kSeriesUnknown;
224  }
225 
226  spec.encoder_cpr = doc[i]["encoder_cpr"].as<uint>();
227  spec.velocity_radps_to_reg = doc[i]["velocity_radps_to_reg"].as<double>();
228  spec.effort_reg_max = doc[i]["effort_reg_max"].as<double>();
229  spec.effort_reg_to_mA = doc[i]["effort_reg_to_mA"].as<double>();
230 
231  if (doc[i]["encoder_range_deg"])
232  {
233  spec.encoder_range_deg = doc[i]["encoder_range_deg"].as<double>();
234  }
235  else
236  {
237  spec.encoder_range_deg = 360;
238  }
239 
240  if (doc[i]["external_ports"])
241  {
242  spec.external_ports = doc[i]["external_ports"].as<bool>();
243  }
244  else
245  {
246  spec.external_ports = false;
247  }
248 
249  ROS_INFO("Model: %s, No: %d, Type: %s", spec.name.c_str(), spec.model_number, type.c_str());
250  model_specs_.insert(std::pair<int, const DynamixelSpec>(spec.model_number, spec));
251  }
252 
253  initialised_ = true;
254  return true;
255 }
256 
260 {
261  if (!loadMotorData())
262  {
263  ROS_ERROR("Unable to parse motor_data.yaml file");
264  return false;
265  }
266 
267  // Open port
268  if (portHandler_->openPort())
269  {
270  ROS_INFO("Succeeded to open the port(%s)!", device_.c_str());
271  }
272  else
273  {
274  ROS_ERROR("Failed to open the port!");
275  return false;
276  }
277 
278  // Set port baudrate
279  if (portHandler_->setBaudRate(baud_rate_))
280  {
281  ROS_INFO("Succeeded to change the baudrate(%d)\n!", portHandler_->getBaudRate());
282  }
283  else
284  {
285  ROS_ERROR("Failed to change the baudrate!");
286  return false;
287  }
288 
289  return true;
290 }
291 
295 bool DynamixelInterfaceDriver::ping(int servo_id) const
296 {
297  uint8_t error;
298  int dxl_comm_result;
299 
300  // ping dynamixel on bus
301  dxl_comm_result = packetHandler_->ping(portHandler_.get(), servo_id, &error);
302 
303  // CHECK IF PING SUCCEEDED
304  if (dxl_comm_result == COMM_SUCCESS)
305  {
306  return true;
307  }
308  else
309  {
310  return false;
311  }
312 }
313 
318 bool DynamixelInterfaceDriver::getModelNumber(int servo_id, uint16_t *model_number) const
319 {
320  uint8_t error;
321  int dxl_comm_result;
322 
323  // read in first 2 bytes of eeprom (same for all series)
324  dxl_comm_result = packetHandler_->read2ByteTxRx(portHandler_.get(), servo_id, 0, model_number, &error);
325 
326  // check return value
327  if (dxl_comm_result == COMM_SUCCESS)
328  {
329  return true;
330  }
331  else
332  {
333  return false;
334  }
335 }
336 
342 bool DynamixelInterfaceDriver::getErrorStatus(int servo_id, DynamixelSeriesType type, uint8_t *error_status) const
343 {
344  uint8_t error;
345  int dxl_comm_result = -1;
346 
347  // Read address and size always depends on servo series
348  switch (type)
349  {
350  case kSeriesAX:
351  case kSeriesRX:
352  case kSeriesDX:
353  case kSeriesEX:
354  case kSeriesLegacyMX:
355  dxl_comm_result = packetHandler_->ping(portHandler_.get(), servo_id, &error);
356  *error_status = error;
357  break;
358 
359  case kSeriesX:
360  case kSeriesMX:
361  dxl_comm_result = packetHandler_->read1ByteTxRx(portHandler_.get(), servo_id, kRegStandard_HardwareErrorStatus,
362  error_status, &error);
363  break;
364 
365  case kSeriesP:
366  dxl_comm_result =
367  packetHandler_->read1ByteTxRx(portHandler_.get(), servo_id, kRegP_HardwareErrorStatus, error_status, &error);
368  break;
369 
370  case kSeriesLegacyPro:
371  dxl_comm_result = packetHandler_->read1ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_HardwareErrorStatus,
372  error_status, &error);
373  break;
374  }
375 
376  // check return value
377  if (dxl_comm_result == COMM_SUCCESS)
378  {
379  return true;
380  }
381  else
382  {
383  return false;
384  }
385 }
386 
392 bool DynamixelInterfaceDriver::getMaxTorque(int servo_id, DynamixelSeriesType type, uint16_t *max_torque) const
393 {
394  uint8_t error;
395  int dxl_comm_result = -1;
396 
397  // Read address and size always depends on servo series
398  switch (type)
399  {
400  case kSeriesAX:
401  case kSeriesRX:
402  case kSeriesDX:
403  case kSeriesEX:
404  case kSeriesLegacyMX:
405  dxl_comm_result = packetHandler_->read1ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_MaxTorque,
406  reinterpret_cast<uint8_t*>(max_torque), &error);
407  break;
408 
409  case kSeriesX:
410  case kSeriesMX:
411  dxl_comm_result =
412  packetHandler_->read2ByteTxRx(portHandler_.get(), servo_id, kRegStandard_CurrentLimit, max_torque, &error);
413  break;
414 
415  case kSeriesP:
416  dxl_comm_result =
417  packetHandler_->read2ByteTxRx(portHandler_.get(), servo_id, kRegP_CurrentLimit, max_torque, &error);
418  break;
419 
420  case kSeriesLegacyPro:
421  dxl_comm_result =
422  packetHandler_->read2ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_MaxTorque, max_torque, &error);
423  break;
424  }
425 
426  // check return value
427  if (dxl_comm_result == COMM_SUCCESS)
428  {
429  return true;
430  }
431  else
432  {
433  return false;
434  }
435 }
436 
442 bool DynamixelInterfaceDriver::getTorqueEnabled(int servo_id, DynamixelSeriesType type, bool *torque_enabled) const
443 {
444  uint8_t error;
445  int dxl_comm_result;
446  uint8_t data = 0;
447 
448  // Read address and size always depends on servo series
449  switch (type)
450  {
451  case kSeriesAX:
452  case kSeriesRX:
453  case kSeriesDX:
454  case kSeriesEX:
455  case kSeriesLegacyMX:
456  dxl_comm_result =
457  packetHandler_->read1ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_TorqueEnable, &data, &error);
458  break;
459 
460  case kSeriesX:
461  case kSeriesMX:
462  dxl_comm_result =
463  packetHandler_->read1ByteTxRx(portHandler_.get(), servo_id, kRegStandard_TorqueEnable, &data, &error);
464  break;
465 
466  case kSeriesP:
467  dxl_comm_result = packetHandler_->read1ByteTxRx(portHandler_.get(), servo_id, kRegP_TorqueEnable, &data, &error);
468  break;
469 
470  case kSeriesLegacyPro:
471  dxl_comm_result =
472  packetHandler_->read1ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_TorqueEnable, &data, &error);
473  break;
474  }
475 
476  // check return value
477  if (dxl_comm_result == COMM_SUCCESS)
478  {
479  *torque_enabled = (data > 0);
480  return true;
481  }
482  else
483  {
484  return false;
485  }
486 }
487 
493 bool DynamixelInterfaceDriver::getTargetTorque(int servo_id, DynamixelSeriesType type, int16_t *target_torque) const
494 {
495  uint8_t error;
496  int dxl_comm_result;
497 
498  // Read address and size always depends on servo series
499  switch (type)
500  {
501  case kSeriesAX:
502  case kSeriesRX:
503  case kSeriesDX:
504  case kSeriesEX:
505  case kSeriesLegacyMX:
506  dxl_comm_result = packetHandler_->read2ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_GoalTorque,
507  reinterpret_cast<uint16_t*>(target_torque), &error);
508  break;
509 
510  case kSeriesX:
511  case kSeriesMX:
512  dxl_comm_result = packetHandler_->read2ByteTxRx(portHandler_.get(), servo_id, kRegStandard_GoalCurrent,
513  reinterpret_cast<uint16_t*>(target_torque), &error);
514  break;
515 
516  case kSeriesP:
517  dxl_comm_result = packetHandler_->read2ByteTxRx(portHandler_.get(), servo_id, kRegP_GoalCurrent,
518  reinterpret_cast<uint16_t*>(target_torque), &error);
519  break;
520 
521  case kSeriesLegacyPro:
522  dxl_comm_result = packetHandler_->read2ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_GoalTorque,
523  reinterpret_cast<uint16_t*>(target_torque), &error);
524  break;
525  }
526 
527  // check return value
528  if (dxl_comm_result == COMM_SUCCESS)
529  {
530  return true;
531  }
532  else
533  {
534  return false;
535  }
536 }
537 
544 bool DynamixelInterfaceDriver::readRegisters(int servo_id, uint16_t address, uint16_t length,
545  std::vector<uint8_t> *response) const
546 {
547  uint8_t error;
548  int dxl_comm_result;
549 
550  // resize output vector for data
551  response->resize(length);
552 
553  dxl_comm_result = packetHandler_->readTxRx(portHandler_.get(), servo_id, address, length, response->data(), &error);
554 
555  // check return value
556  if (dxl_comm_result == COMM_SUCCESS)
557  {
558  return true;
559  }
560  else
561  {
562  return false;
563  }
564 }
565 
566 // *********************** BULK_READ METHODS *************************** //
567 
574 bool DynamixelInterfaceDriver::getBulkState(std::unordered_map<int, DynamixelState> &state_map) const
575 {
576  bool success = false;
577  std::unordered_map<int, SyncData*> read_map;
578  uint i = 0;
579 
580  // base case, nothing to read
581  if (state_map.size() == 0)
582  {
583  return true;
584  }
585 
586  for (auto &it : state_map)
587  {
588  it.second.success = false;
589  read_map[it.first] = static_cast<SyncData*>(&it.second);
590  }
591 
592  // perform bulk read depending on type
593  DynamixelSeriesType type = state_map.begin()->second.type;
594  switch (type)
595  {
596  case kSeriesAX:
597  case kSeriesRX:
598  case kSeriesDX:
599  case kSeriesEX:
600  case kSeriesLegacyMX:
601  // read data
602  if (use_group_read_)
603  {
604  bulkRead(read_map, kRegLegacy_PresentPosition, 6); // bulk method
605  }
606  else
607  {
608  for (auto &it : state_map)
609  {
610  if (readRegisters(it.first, kRegLegacy_PresentPosition, 6, &it.second.data)) // individual reads
611  {
612  it.second.success = true;
613  }
614  else
615  {
616  it.second.success = false;
617  }
618  }
619  }
620 
621  for (auto &it : state_map) // decode responses
622  {
623  if (it.second.success)
624  {
625  it.second.position = *(reinterpret_cast<int16_t*>(&it.second.data[0]));
626  it.second.velocity = *(reinterpret_cast<int16_t*>(&it.second.data[2]));
627  it.second.effort = *(reinterpret_cast<int16_t*>(&it.second.data[4]));
628  success = true;
629  }
630  }
631  return success;
632 
633  case kSeriesMX:
634  case kSeriesX:
635  // read data
636  if (use_group_read_)
637  {
638  syncRead(read_map, kRegStandard_PresentCurrent, 10); // bulk method
639  }
640  else
641  {
642  for (auto &it : state_map)
643  {
644  if (readRegisters(it.first, kRegStandard_PresentCurrent, 10, &it.second.data)) // individual reads
645  {
646  it.second.success = true;
647  }
648  else
649  {
650  it.second.success = false;
651  }
652  }
653  }
654  for (auto &it : state_map) // decode responses
655  {
656  if (it.second.success)
657  {
658  it.second.effort = *(reinterpret_cast<int16_t*>(&it.second.data[0]));
659  it.second.velocity = *(reinterpret_cast<int32_t*>(&it.second.data[2]));
660  it.second.position = *(reinterpret_cast<int32_t*>(&it.second.data[6]));
661  success = true;
662  }
663  }
664  return success;
665 
666  case kSeriesP:
667  // read data
668  if (use_group_read_)
669  {
670  syncRead(read_map, kRegP_PresentCurrent, 10); // bulk method
671  }
672  else
673  {
674  for (auto &it : state_map)
675  {
676  if (readRegisters(it.first, kRegP_PresentCurrent, 10, &it.second.data)) // individual reads
677  {
678  it.second.success = true;
679  }
680  else
681  {
682  it.second.success = false;
683  }
684  }
685  }
686  for (auto &it : state_map) // decode responses
687  {
688  if (it.second.success)
689  {
690  it.second.effort = *(reinterpret_cast<int16_t*>(&it.second.data[0]));
691  it.second.velocity = *(reinterpret_cast<int32_t*>(&it.second.data[2]));
692  it.second.position = *(reinterpret_cast<int32_t*>(&it.second.data[6]));
693  success = true;
694  }
695  }
696  return success;
697 
698  case kSeriesLegacyPro:
699  // read data
700  if (use_group_read_)
701  {
702  bulkRead(read_map, kRegLegacyPro_PresentPosition, 10); // bulk method
703  }
704  else
705  {
706  for (auto &it : state_map)
707  {
708  if (readRegisters(it.first, kRegLegacyPro_PresentPosition, 10, &it.second.data)) // individual reads
709  {
710  it.second.success = true;
711  }
712  else
713  {
714  it.second.success = false;
715  }
716  }
717  }
718  for (auto &it : state_map) // decode responses
719  {
720  if (it.second.success)
721  {
722  it.second.position = *(reinterpret_cast<int32_t*>(&it.second.data[0]));
723  it.second.velocity = *(reinterpret_cast<int32_t*>(&it.second.data[4]));
724  it.second.effort = *(reinterpret_cast<int16_t*>(&it.second.data[8]));
725  success = true;
726  }
727  }
728  return success;
729 
730  default:
731  // ROS_WARN("BAD TYPE: %d", type);
732  return false;
733  }
734 
735  // ROS_WARN("FAIL OUT OF FUNCTION");
736  return false;
737 }
738 
742 bool DynamixelInterfaceDriver::getBulkDataportInfo(std::unordered_map<int, DynamixelDataport> &data_map) const
743 {
744  bool success = false;
745  std::unordered_map<int, SyncData*> read_map;
746  uint i = 0;
747 
748  // base case, nothing to read
749  if (data_map.size() == 0)
750  {
751  return true;
752  }
753 
754  for (auto &it : data_map)
755  {
756  it.second.success = false;
757  read_map[it.first] = static_cast<SyncData*>(&it.second);
758  }
759 
760  // perform bulk read depending on type
761  DynamixelSeriesType type = data_map.begin()->second.type;
762  switch (type)
763  {
764  case kSeriesX:
765  // read data
766  if (use_group_read_)
767  {
768  syncRead(read_map, kRegStandard_DataPort1, 6);
769  }
770  else
771  {
772  for (auto &it : data_map)
773  {
774  if (readRegisters(it.first, kRegStandard_DataPort1, 6, &it.second.data)) // individual reads
775  {
776  it.second.success = true;
777  }
778  else
779  {
780  it.second.success = false;
781  }
782  }
783  }
784  for (auto &it : data_map) // decode responses
785  {
786  if (it.second.success)
787  {
788  it.second.port_values[0] = *(reinterpret_cast<uint16_t*>(&it.second.data[0]));
789  it.second.port_values[1] = *(reinterpret_cast<uint16_t*>(&it.second.data[2]));
790  it.second.port_values[2] = *(reinterpret_cast<uint16_t*>(&it.second.data[4]));
791  it.second.port_values[4] = 0;
792  success = true;
793  }
794  }
795 
796  return success;
797 
798  // NEW PRO SERIES
799  case kSeriesP:
800  // read data
801  if (use_group_read_)
802  {
803  syncRead(read_map, kRegP_DataPort1, 8); // bulk method
804  }
805  else
806  {
807  for (auto &it : data_map)
808  {
809  if (readRegisters(it.first, kRegP_DataPort1, 8, &it.second.data)) // individual reads
810  {
811  it.second.success = true;
812  }
813  else
814  {
815  it.second.success = false;
816  }
817  }
818  }
819  for (auto &it : data_map) // decode responses
820  {
821  if (it.second.success)
822  {
823  it.second.port_values[0] = *(reinterpret_cast<uint16_t*>(&it.second.data[0]));
824  it.second.port_values[1] = *(reinterpret_cast<uint16_t*>(&it.second.data[2]));
825  it.second.port_values[2] = *(reinterpret_cast<uint16_t*>(&it.second.data[4]));
826  it.second.port_values[3] = *(reinterpret_cast<uint16_t*>(&it.second.data[6]));
827  success = true;
828  }
829  }
830  return success;
831 
832  // OLD PRO SERIES
833  case kSeriesLegacyPro:
834  // read data
835  if (use_group_read_)
836  {
837  syncRead(read_map, kRegLegacyPro_DataPort1, 8); // bulk method
838  }
839  else
840  {
841  for (auto &it : data_map)
842  {
843  if (readRegisters(it.first, kRegLegacyPro_DataPort1, 8, &it.second.data)) // individual reads
844  {
845  it.second.success = true;
846  }
847  else
848  {
849  it.second.success = false;
850  }
851  }
852  }
853  for (auto &it : data_map) // decode responses
854  {
855  if (it.second.success)
856  {
857  it.second.port_values[0] = *(reinterpret_cast<uint16_t*>(&it.second.data[0]));
858  it.second.port_values[1] = *(reinterpret_cast<uint16_t*>(&it.second.data[2]));
859  it.second.port_values[2] = *(reinterpret_cast<uint16_t*>(&it.second.data[4]));
860  it.second.port_values[3] = *(reinterpret_cast<uint16_t*>(&it.second.data[6]));
861  success = true;
862  }
863  }
864  return success;
865 
866  default:
867  return false;
868  }
869 
870  return false;
871 }
872 
876 bool DynamixelInterfaceDriver::getBulkDiagnosticInfo(std::unordered_map<int, DynamixelDiagnostic> &diag_map) const
877 {
878  bool success = false;
879  std::unordered_map<int, SyncData*> read_map;
880  uint i = 0;
881 
882  // base case, nothing to read
883  if (diag_map.size() == 0)
884  {
885  return true;
886  }
887 
888  for (auto &it : diag_map)
889  {
890  it.second.success = false;
891  read_map[it.first] = static_cast<SyncData*>(&it.second);
892  }
893 
894  // perform bulk read depending on type
895  DynamixelSeriesType type = diag_map.begin()->second.type;
896  switch (type)
897  {
898  // OLDER, DISCONTINUED SERIES
899  case kSeriesAX:
900  case kSeriesRX:
901  case kSeriesDX:
902  case kSeriesEX:
903  case kSeriesLegacyMX:
904  // read data
905  if (use_group_read_)
906  {
907  bulkRead(read_map, kRegLegacy_PresentVoltage, 2); // bulk method
908  }
909  else
910  {
911  for (auto &it : diag_map)
912  {
913  if (readRegisters(it.first, kRegLegacy_PresentVoltage, 2, &it.second.data)) // individual reads
914  {
915  it.second.success = true;
916  }
917  else
918  {
919  it.second.success = false;
920  }
921  }
922  }
923  for (auto &it : diag_map) // decode responses
924  {
925  if (it.second.success)
926  {
927  it.second.voltage = it.second.data[0];
928  it.second.temperature = it.second.data[1];
929  success = true;
930  }
931  }
932  return success;
933 
934  // NEW MX AND X SERIES
935  case kSeriesMX:
936  case kSeriesX:
937  // read data
938  if (use_group_read_)
939  {
941  }
942  else
943  {
944  for (auto &it : diag_map)
945  {
946  if (readRegisters(it.first, kRegStandard_PresentInputVoltage, 3, &it.second.data)) // individual reads
947  {
948  it.second.success = true;
949  }
950  else
951  {
952  it.second.success = false;
953  }
954  }
955  }
956  for (auto &it : diag_map) // decode responses
957  {
958  if (it.second.success)
959  {
960  it.second.voltage = *(reinterpret_cast<uint16_t*>(&it.second.data[6]));
961  it.second.temperature = it.second.data[2];
962  success = true;
963  }
964  }
965 
966  return success;
967 
968  // NEW PRO SERIES
969  case kSeriesP:
970  // read data
971  if (use_group_read_)
972  {
973  syncRead(read_map, kRegP_PresentInputVoltage, 3); // bulk method
974  }
975  else
976  {
977  for (auto &it : diag_map)
978  {
979  if (readRegisters(it.first, kRegP_PresentInputVoltage, 3, &it.second.data)) // individual reads
980  {
981  it.second.success = true;
982  }
983  else
984  {
985  it.second.success = false;
986  }
987  }
988  }
989  for (auto &it : diag_map) // decode responses
990  {
991  if (it.second.success)
992  {
993  it.second.voltage = *(reinterpret_cast<uint16_t*>(&it.second.data[0]));
994  it.second.temperature = it.second.data[2];
995  success = true;
996  }
997  }
998  return success;
999 
1000  // OLD PRO SERIES
1001  case kSeriesLegacyPro:
1002  // read data
1003  if (use_group_read_)
1004  {
1005  syncRead(read_map, kRegLegacyPro_PresentVoltage, 3); // bulk method
1006  }
1007  else
1008  {
1009  for (auto &it : diag_map)
1010  {
1011  if (readRegisters(it.first, kRegLegacyPro_PresentVoltage, 3, &it.second.data)) // individual reads
1012  {
1013  it.second.success = true;
1014  }
1015  else
1016  {
1017  it.second.success = false;
1018  }
1019  }
1020  }
1021  for (auto &it : diag_map) // decode responses
1022  {
1023  if (it.second.success)
1024  {
1025  it.second.voltage = *(reinterpret_cast<uint16_t*>(&it.second.data[0]));
1026  it.second.temperature = it.second.data[2];
1027  success = true;
1028  }
1029  }
1030  return success;
1031 
1032  default:
1033  return false;
1034  }
1035 
1036  return false;
1037 }
1038 
1039 // ********************** Protected Read Methods *********************** //
1040 
1049 bool DynamixelInterfaceDriver::bulkRead(std::unordered_map<int, SyncData*> &read_data, uint16_t address,
1050  uint16_t length) const
1051 {
1052  int dxl_comm_result;
1053  bool success = false;
1054 
1055  // Initialize GroupSyncRead instance
1056  dynamixel::GroupBulkRead GroupBulkRead(portHandler_.get(), packetHandler_.get());
1057 
1058  // add all dynamixels to sync read
1059  for (auto &it : read_data)
1060  {
1061  GroupBulkRead.addParam(it.first, address, length);
1062  // clear data in response object
1063  it.second->data.clear();
1064  }
1065 
1066  // perform sync read
1067  dxl_comm_result = GroupBulkRead.txRxPacket();
1068 
1069  if (dxl_comm_result != COMM_SUCCESS)
1070  {
1071  return false;
1072  }
1073 
1074  // get all responses back from read
1075  for (auto &it : read_data)
1076  {
1077  // if data available
1078  if (GroupBulkRead.isAvailable(it.first, address, length))
1079  {
1080  // have at least one response
1081  success = true;
1082 
1083  // Get values from read and place into vector
1084  for (int j = 0; j < length; j++)
1085  {
1086  it.second->data.push_back(GroupBulkRead.getData(it.first, address + j, 1));
1087  }
1088  it.second->success = true;
1089  }
1090  // also get and store error code
1091  GroupBulkRead.getError(it.first, &(it.second->error));
1092  }
1093 
1094  if (!success)
1095  {
1096  return false;
1097  }
1098  else
1099  {
1100  return true;
1101  }
1102 }
1103 
1111 bool DynamixelInterfaceDriver::syncRead(std::unordered_map<int, SyncData*> &read_data, uint16_t address,
1112  uint16_t length) const
1113 {
1114  int dxl_comm_result;
1115  bool success = false;
1116 
1118  {
1119  return false;
1120  }
1121 
1122  // Initialize GroupSyncRead instance
1123  dynamixel::GroupSyncRead GroupSyncRead(portHandler_.get(), packetHandler_.get(), address, length);
1124 
1125  // add all dynamixels to sync read
1126  for (auto &it : read_data)
1127  {
1128  GroupSyncRead.addParam(it.first);
1129  // clear data in response object
1130  it.second->data.clear();
1131  }
1132 
1133  // perform sync read
1134  dxl_comm_result = GroupSyncRead.txRxPacket();
1135 
1136  if (dxl_comm_result != COMM_SUCCESS)
1137  {
1138  return false;
1139  }
1140 
1141  // get all responses back from read
1142  for (auto &it : read_data)
1143  {
1144  // if data available
1145  if (GroupSyncRead.isAvailable(it.first, address, length))
1146  {
1147  // have at least one response
1148  success = true;
1149  // Get values from read and place into vector
1150  for (int j = 0; j < length; j++)
1151  {
1152  it.second->data.push_back(GroupSyncRead.getData(it.first, address + j, 1));
1153  }
1154  it.second->success = true;
1155  }
1156  else
1157  {
1158  it.second->success = false;
1159  }
1160  // also get and store error code
1161  GroupSyncRead.getError(it.first, &(it.second->error));
1162  }
1163 
1164  if (!success)
1165  {
1166  return false;
1167  }
1168  else
1169  {
1170  return true;
1171  }
1172 }
1173 
1174 // **************************** SETTERS ******************************** //
1175 
1186  DynamixelControlMode operating_mode) const
1187 {
1188  uint8_t error;
1189  int dxl_comm_result = 0;
1190  uint16_t model_num;
1191  bool success = true;
1192 
1193  // Read address and size always depends on servo series
1194  switch (type)
1195  {
1196  case kSeriesAX:
1197  case kSeriesRX:
1198  case kSeriesDX:
1199  case kSeriesEX:
1200  case kSeriesLegacyMX:
1201 
1202  // MX Series has no operating mode register, instead operating mode depends on
1203  // angle limits
1204  switch (operating_mode)
1205  {
1206  case kModePositionControl:
1207 
1208  // Position control, set normal angle limits
1209  success = setAngleLimits(servo_id, type, 0, 4095); // Master mode, normal roatation
1210  break;
1211 
1212  case kModeVelocityControl:
1213 
1214  // Velocity control, turn off angle limits
1215  success = setAngleLimits(servo_id, type, 0, 0); // Master mode, normal roatation
1216  break;
1217 
1218  case kModeTorqueControl:
1219  break;
1220  }
1221  break;
1222 
1223  case kSeriesMX:
1224  case kSeriesX:
1225 
1226  if ((operating_mode == kModeTorqueControl) || (operating_mode == kModeCurrentBasedPositionControl))
1227  {
1228  success = getModelNumber(servo_id, &model_num);
1229 
1230  if (success && (model_num != 30))
1231  {
1232  dxl_comm_result = packetHandler_->write1ByteTxRx(portHandler_.get(), servo_id, kRegStandard_OperatingMode,
1233  operating_mode, &error);
1234  }
1235  }
1236  else
1237  {
1238  dxl_comm_result = packetHandler_->write1ByteTxRx(portHandler_.get(), servo_id, kRegStandard_OperatingMode,
1239  operating_mode, &error);
1240  }
1241  break;
1242 
1243  case kSeriesP:
1244 
1245  dxl_comm_result =
1246  packetHandler_->write1ByteTxRx(portHandler_.get(), servo_id, kRegP_OperatingMode, operating_mode, &error);
1247  break;
1248 
1249  case kSeriesLegacyPro:
1250 
1251  if (operating_mode != kModePWMControl)
1252  {
1253  dxl_comm_result = packetHandler_->write1ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_OperatingMode,
1254  operating_mode, &error);
1255  }
1256  break;
1257 
1258  default:
1259  return false;
1260  }
1261 
1262  // check return value
1263  if ((dxl_comm_result == COMM_SUCCESS) && (success))
1264  {
1265  return true;
1266  }
1267  else
1268  {
1269  return false;
1270  }
1271 }
1272 
1279 bool DynamixelInterfaceDriver::setAngleLimits(int servo_id, DynamixelSeriesType type, int32_t min_angle,
1280  int32_t max_angle) const
1281 {
1282  if (setMaxAngleLimit(servo_id, type, max_angle) == true)
1283  {
1284  return setMinAngleLimit(servo_id, type, min_angle);
1285  }
1286  else
1287  {
1288  return false;
1289  }
1290 }
1291 
1297 bool DynamixelInterfaceDriver::setMinAngleLimit(int servo_id, DynamixelSeriesType type, int32_t angle) const
1298 {
1299  uint8_t error;
1300  int dxl_comm_result;
1301 
1302  switch (type)
1303  {
1304  case kSeriesAX:
1305  case kSeriesRX:
1306  case kSeriesDX:
1307  case kSeriesEX:
1308  case kSeriesLegacyMX:
1309  dxl_comm_result =
1310  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_CWAngleLimit, (int16_t)angle, &error);
1311  break;
1312 
1313  case kSeriesMX:
1314  case kSeriesX:
1315  dxl_comm_result =
1316  packetHandler_->write4ByteTxRx(portHandler_.get(), servo_id, kRegStandard_MinPositionLimit, angle, &error);
1317  break;
1318 
1319  case kSeriesP:
1320  dxl_comm_result =
1321  packetHandler_->write4ByteTxRx(portHandler_.get(), servo_id, kRegP_MinPositionLimit, angle, &error);
1322  break;
1323 
1324  case kSeriesLegacyPro:
1325  dxl_comm_result =
1326  packetHandler_->write4ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_MinAngleLimit, angle, &error);
1327  break;
1328  }
1329 
1330  // check return value
1331  if (dxl_comm_result == COMM_SUCCESS)
1332  {
1333  return true;
1334  }
1335  else
1336  {
1337  return false;
1338  }
1339 }
1340 
1346 bool DynamixelInterfaceDriver::setMaxAngleLimit(int servo_id, DynamixelSeriesType type, int32_t angle) const
1347 {
1348  uint8_t error;
1349  int dxl_comm_result;
1350 
1351  switch (type)
1352  {
1353  case kSeriesAX:
1354  case kSeriesRX:
1355  case kSeriesDX:
1356  case kSeriesEX:
1357  case kSeriesLegacyMX:
1358  dxl_comm_result =
1359  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_CCWAngleLimit, (int16_t)angle, &error);
1360  break;
1361 
1362  case kSeriesMX:
1363  case kSeriesX:
1364  dxl_comm_result =
1365  packetHandler_->write4ByteTxRx(portHandler_.get(), servo_id, kRegStandard_MaxPositionLimit, angle, &error);
1366  break;
1367 
1368  case kSeriesP:
1369  dxl_comm_result =
1370  packetHandler_->write4ByteTxRx(portHandler_.get(), servo_id, kRegP_MaxPositionLimit, angle, &error);
1371  break;
1372 
1373  case kSeriesLegacyPro:
1374  dxl_comm_result =
1375  packetHandler_->write4ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_MaxAngleLimit, angle, &error);
1376  break;
1377  }
1378 
1379  // check return value
1380  if (dxl_comm_result == COMM_SUCCESS)
1381  {
1382  return true;
1383  }
1384  else
1385  {
1386  return false;
1387  }
1388 }
1389 
1395 bool DynamixelInterfaceDriver::setMaxTorque(int servo_id, DynamixelSeriesType type, uint16_t max_torque) const
1396 {
1397  uint8_t error;
1398  int dxl_comm_result;
1399 
1400  // Read address and size always depends on servo series
1401  switch (type)
1402  {
1403  case kSeriesAX:
1404  case kSeriesRX:
1405  case kSeriesDX:
1406  case kSeriesEX:
1407  case kSeriesLegacyMX:
1408  dxl_comm_result =
1409  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_MaxTorque, max_torque, &error);
1410  dxl_comm_result =
1411  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_TorqueLimit, max_torque, &error);
1412 
1413  case kSeriesMX:
1414  case kSeriesX:
1415  dxl_comm_result =
1416  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegStandard_CurrentLimit, max_torque, &error);
1417  break;
1418 
1419  case kSeriesP:
1420  dxl_comm_result =
1421  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegP_CurrentLimit, max_torque, &error);
1422  dxl_comm_result =
1423  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegP_GoalCurrent, max_torque, &error);
1424  break;
1425 
1426  case kSeriesLegacyPro:
1427  dxl_comm_result =
1428  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_MaxTorque, max_torque, &error);
1429  dxl_comm_result =
1430  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_GoalTorque, max_torque, &error);
1431  break;
1432  }
1433 
1434  // check return value
1435  if (dxl_comm_result == COMM_SUCCESS)
1436  {
1437  return true;
1438  }
1439  else
1440  {
1441  return false;
1442  }
1443 }
1444 
1450 bool DynamixelInterfaceDriver::setMaxVelocity(int servo_id, DynamixelSeriesType type, uint32_t max_vel) const
1451 {
1452  uint8_t error;
1453  int dxl_comm_result;
1454 
1455  // Read address and size always depends on servo series
1456  switch (type)
1457  {
1458  case kSeriesAX:
1459  case kSeriesRX:
1460  case kSeriesDX:
1461  case kSeriesEX:
1462  case kSeriesLegacyMX:
1463  break;
1464 
1465  case kSeriesMX:
1466  case kSeriesX:
1467  dxl_comm_result =
1468  packetHandler_->write4ByteTxRx(portHandler_.get(), servo_id, kRegStandard_VelocityLimit, max_vel, &error);
1469  break;
1470 
1471  case kSeriesP:
1472  dxl_comm_result =
1473  packetHandler_->write4ByteTxRx(portHandler_.get(), servo_id, kRegP_VelocityLimit, max_vel, &error);
1474  break;
1475 
1476  case kSeriesLegacyPro:
1477  dxl_comm_result =
1478  packetHandler_->write4ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_VelocityLimit, max_vel, &error);
1479  break;
1480  }
1481 
1482  // check return value
1483  if (dxl_comm_result == COMM_SUCCESS)
1484  {
1485  return true;
1486  }
1487  else
1488  {
1489  return false;
1490  }
1491 }
1492 
1499 {
1500  uint8_t error;
1501  int dxl_comm_result;
1502 
1503  // Read address and size always depends on servo series
1504  switch (type)
1505  {
1506  case kSeriesAX:
1507  case kSeriesRX:
1508  case kSeriesDX:
1509  case kSeriesEX:
1510  case kSeriesLegacyMX:
1511  dxl_comm_result =
1512  packetHandler_->write1ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_TorqueEnable, (uint8_t)on, &error);
1513  break;
1514 
1515  case kSeriesMX:
1516  case kSeriesX:
1517  dxl_comm_result =
1518  packetHandler_->write1ByteTxRx(portHandler_.get(), servo_id, kRegStandard_TorqueEnable, (uint8_t)on, &error);
1519  break;
1520 
1521  case kSeriesP:
1522  dxl_comm_result =
1523  packetHandler_->write1ByteTxRx(portHandler_.get(), servo_id, kRegP_TorqueEnable, (uint8_t)on, &error);
1524  break;
1525 
1526  case kSeriesLegacyPro:
1527  dxl_comm_result =
1528  packetHandler_->write1ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_TorqueEnable, (uint8_t)on, &error);
1529  break;
1530  }
1531 
1532  // check return value
1533  if (dxl_comm_result == COMM_SUCCESS)
1534  {
1535  return true;
1536  }
1537  else
1538  {
1539  return false;
1540  }
1541 }
1542 
1550 {
1551  uint8_t error;
1552  uint16_t model_num;
1553  int dxl_comm_result;
1554 
1555  // Torque control mode, there is actually a register for this
1556  getModelNumber(servo_id, &model_num);
1557  if ((model_num == 310) || (model_num == 320)) // No torque control on MX-28
1558  {
1559  dxl_comm_result = packetHandler_->write1ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_TorqueControlEnable,
1560  (uint8_t)(on), &error);
1561  }
1562  else
1563  {
1564  return false;
1565  }
1566 
1567  // check return value
1568  if (dxl_comm_result == COMM_SUCCESS)
1569  {
1570  return true;
1571  }
1572  else
1573  {
1574  return false;
1575  }
1576 }
1577 
1585 bool DynamixelInterfaceDriver::setPositionPIDGains(int servo_id, DynamixelSeriesType type, double p_gain, double i_gain,
1586  double d_gain) const
1587 {
1588  uint16_t p_val, i_val, d_val;
1589 
1590  // Convert values based on servo series
1591  switch (type)
1592  {
1593  case kSeriesLegacyMX:
1594  p_val = (uint16_t)(p_gain * 8.0);
1595  i_val = (uint16_t)(i_gain * (1000.0 / 2048.0));
1596  d_val = (uint16_t)(d_gain / (4.0 / 1000.0));
1597  break;
1598 
1599  case kSeriesMX:
1600  case kSeriesX:
1601  p_val = (uint16_t)(p_gain * 128.0); // possible 0-127
1602  i_val = (uint16_t)(i_gain * 65536.0); // by the same logic, 0-0.25
1603  d_val = (uint16_t)(d_gain * 16.0); // 0-1024
1604  break;
1605 
1606  case kSeriesP:
1607  p_val = (uint16_t)p_gain;
1608  i_val = 0;
1609  d_val = 0;
1610  break;
1611 
1612  default:
1613  return false;
1614  }
1615 
1616  // set the register values for the given control mode,
1617  // This changes based on servo series, a value of gain < 0
1618  // indicates that the gain should be left to the default
1619  if (!(p_gain < 0))
1620  {
1621  if (!setPositionProportionalGain(servo_id, type, p_val))
1622  {
1623  return false;
1624  }
1625  }
1626 
1627  if (!(i_gain < 0) && (type != kSeriesLegacyPro))
1628  {
1629  if (!setPositionIntegralGain(servo_id, type, i_val))
1630  {
1631  return false;
1632  }
1633  }
1634 
1635  if (!(d_gain < 0) && (type != kSeriesLegacyPro))
1636  {
1637  if (!setPositionDerivativeGain(servo_id, type, d_val))
1638  {
1639  return false;
1640  }
1641  }
1642 
1643  return true;
1644 }
1645 
1652 {
1653  uint8_t error;
1654  int dxl_comm_result;
1655 
1656  // Read address and size always depends on servo series
1657  switch (type)
1658  {
1659  case kSeriesAX:
1660  case kSeriesRX:
1661  case kSeriesDX:
1662  case kSeriesEX:
1663  return false;
1664 
1665  case kSeriesLegacyMX:
1666  dxl_comm_result = packetHandler_->write1ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_PGain,
1667  (uint8_t)(gain & 0x00FF), &error);
1668  break;
1669 
1670  case kSeriesMX:
1671  case kSeriesX:
1672  dxl_comm_result =
1673  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegStandard_PositionPGain, gain, &error);
1674  break;
1675 
1676  case kSeriesP:
1677  dxl_comm_result = packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegP_PositionPGain, gain, &error);
1678  break;
1679 
1680  case kSeriesLegacyPro:
1681  dxl_comm_result =
1682  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_PositionPGain, gain, &error);
1683  break;
1684  }
1685 
1686  // check return value
1687  if (dxl_comm_result == COMM_SUCCESS)
1688  {
1689  return true;
1690  }
1691  else
1692  {
1693  return false;
1694  }
1695 }
1696 
1702 bool DynamixelInterfaceDriver::setPositionIntegralGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const
1703 {
1704  uint8_t error;
1705  int dxl_comm_result;
1706 
1707  // Read address and size always depends on servo series
1708  switch (type)
1709  {
1710  case kSeriesAX:
1711  case kSeriesRX:
1712  case kSeriesDX:
1713  case kSeriesEX:
1714  return false;
1715 
1716  case kSeriesLegacyMX:
1717  dxl_comm_result = packetHandler_->write1ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_IGain,
1718  (uint8_t)(gain & 0x00FF), &error);
1719  break;
1720 
1721  case kSeriesMX:
1722  case kSeriesX:
1723  dxl_comm_result =
1724  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegStandard_PositionIGain, gain, &error);
1725  break;
1726 
1727  case kSeriesP:
1728  dxl_comm_result = packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegP_PositionIGain, gain, &error);
1729  break;
1730 
1731  case kSeriesLegacyPro:
1732  return false;
1733  }
1734 
1735  // check return value
1736  if (dxl_comm_result == COMM_SUCCESS)
1737  {
1738  return true;
1739  }
1740  else
1741  {
1742  return false;
1743  }
1744 }
1745 
1752 {
1753  uint8_t error;
1754  int dxl_comm_result;
1755 
1756  // Read address and size always depends on servo series
1757  switch (type)
1758  {
1759  case kSeriesAX:
1760  case kSeriesRX:
1761  case kSeriesDX:
1762  case kSeriesEX:
1763  return false;
1764 
1765  case kSeriesLegacyMX:
1766  dxl_comm_result = packetHandler_->write1ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_DGain,
1767  (uint8_t)(gain & 0x00FF), &error);
1768  break;
1769 
1770  case kSeriesMX:
1771  case kSeriesX:
1772  dxl_comm_result =
1773  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegStandard_PositionDGain, gain, &error);
1774  break;
1775 
1776  case kSeriesP:
1777  dxl_comm_result = packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegP_PositionDGain, gain, &error);
1778  break;
1779 
1780  case kSeriesLegacyPro:
1781  return false;
1782  }
1783 
1784  // check return value
1785  if (dxl_comm_result == COMM_SUCCESS)
1786  {
1787  return true;
1788  }
1789  else
1790  {
1791  return false;
1792  }
1793 }
1794 
1803  double i_gain) const
1804 {
1805  uint16_t p_val, i_val, d_val;
1806 
1807  // Convert values based on servo series
1808  switch (type)
1809  {
1810  case kSeriesMX:
1811  case kSeriesX:
1812  p_val = (uint16_t)(p_gain * 128.0); // possible 0-127
1813  i_val = (uint16_t)(i_gain * 65536.0); // by the same logic, 0-0.25
1814  break;
1815 
1816  case kSeriesP:
1817  p_val = (uint16_t)p_gain;
1818  i_val = (uint16_t)i_gain;
1819  break;
1820 
1821  default:
1822  return false;
1823  }
1824 
1825  // set the register values for the given control mode,
1826  // This changes based on servo series, a value of gain < 0
1827  // indicates that the gain should be left to the default
1828  if (!(p_gain < 0))
1829  {
1830  if (!setVelocityProportionalGain(servo_id, type, p_val))
1831  {
1832  return false;
1833  }
1834  }
1835 
1836  if (!(i_gain < 0))
1837  {
1838  if (!setVelocityIntegralGain(servo_id, type, i_val))
1839  {
1840  return false;
1841  }
1842  }
1843 
1844  return true;
1845 }
1846 
1853 {
1854  uint8_t error;
1855  int dxl_comm_result;
1856 
1857  switch (type)
1858  {
1859  case kSeriesAX:
1860  case kSeriesRX:
1861  case kSeriesDX:
1862  case kSeriesEX:
1863  case kSeriesLegacyMX:
1864  return false;
1865 
1866  case kSeriesMX:
1867  case kSeriesX:
1868  dxl_comm_result =
1869  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegStandard_VelocityPGain, gain, &error);
1870  break;
1871 
1872  case kSeriesP:
1873  dxl_comm_result = packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegP_VelocityPGain, gain, &error);
1874  break;
1875 
1876  case kSeriesLegacyPro:
1877  dxl_comm_result =
1878  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_VelocityPGain, gain, &error);
1879  break;
1880  }
1881 
1882  // check return value
1883  if (dxl_comm_result == COMM_SUCCESS)
1884  {
1885  return true;
1886  }
1887  else
1888  {
1889  return false;
1890  }
1891 }
1892 
1898 bool DynamixelInterfaceDriver::setVelocityIntegralGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const
1899 {
1900  uint8_t error;
1901  int dxl_comm_result;
1902 
1903  switch (type)
1904  {
1905  case kSeriesAX:
1906  case kSeriesRX:
1907  case kSeriesDX:
1908  case kSeriesEX:
1909  case kSeriesLegacyMX:
1910  return false;
1911 
1912  case kSeriesMX:
1913  case kSeriesX:
1914  dxl_comm_result =
1915  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegStandard_VelocityIGain, gain, &error);
1916  break;
1917 
1918  case kSeriesP:
1919  dxl_comm_result = packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegP_VelocityIGain, gain, &error);
1920  break;
1921 
1922  case kSeriesLegacyPro:
1923  dxl_comm_result =
1924  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_VelocityIGain, gain, &error);
1925  break;
1926  }
1927 
1928  // check return value
1929  if (dxl_comm_result == COMM_SUCCESS)
1930  {
1931  return true;
1932  }
1933  else
1934  {
1935  return false;
1936  }
1937 }
1938 
1944 bool DynamixelInterfaceDriver::setProfileVelocity(int servo_id, DynamixelSeriesType type, int32_t velocity) const
1945 {
1946  // Read address and size always depends on servo series
1947  uint8_t error;
1948  int dxl_comm_result;
1949 
1950  switch (type)
1951  {
1952  case kSeriesAX:
1953  case kSeriesRX:
1954  case kSeriesDX:
1955  case kSeriesEX:
1956  case kSeriesLegacyMX:
1957  dxl_comm_result = packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_MovingSpeed,
1958  (uint16_t)velocity, &error);
1959  return false;
1960 
1961  case kSeriesMX:
1962  case kSeriesX:
1963  dxl_comm_result =
1964  packetHandler_->write4ByteTxRx(portHandler_.get(), servo_id, kRegStandard_ProfileVelocity, velocity, &error);
1965  break;
1966 
1967  case kSeriesP:
1968  dxl_comm_result =
1969  packetHandler_->write4ByteTxRx(portHandler_.get(), servo_id, kRegP_ProfileVelocity, velocity, &error);
1970  break;
1971 
1972  case kSeriesLegacyPro:
1973  dxl_comm_result =
1974  packetHandler_->write4ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_GoalVelocity, velocity, &error);
1975  break;
1976  }
1977 
1978  // check return value
1979  if (dxl_comm_result == COMM_SUCCESS)
1980  {
1981  return true;
1982  }
1983  else
1984  {
1985  return false;
1986  }
1987 }
1988 
1994 bool DynamixelInterfaceDriver::setTorque(int servo_id, DynamixelSeriesType type, int16_t torque) const
1995 {
1996  uint8_t error;
1997  int dxl_comm_result;
1998 
1999  switch (type)
2000  {
2001  case kSeriesAX:
2002  case kSeriesRX:
2003  case kSeriesDX:
2004  case kSeriesEX:
2005  return false;
2006 
2007  case kSeriesLegacyMX:
2008  dxl_comm_result =
2009  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegLegacy_GoalTorque, torque, &error);
2010  return false;
2011 
2012  case kSeriesMX:
2013  case kSeriesX:
2014  dxl_comm_result =
2015  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegStandard_GoalCurrent, torque, &error);
2016  break;
2017 
2018  case kSeriesP:
2019  dxl_comm_result = packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegP_GoalCurrent, torque, &error);
2020  break;
2021 
2022  case kSeriesLegacyPro:
2023  dxl_comm_result =
2024  packetHandler_->write2ByteTxRx(portHandler_.get(), servo_id, kRegLegacyPro_GoalTorque, torque, &error);
2025  break;
2026  }
2027 
2028  // check return value
2029  if (dxl_comm_result == COMM_SUCCESS)
2030  {
2031  return true;
2032  }
2033  else
2034  {
2035  return false;
2036  }
2037 }
2038 
2046 bool DynamixelInterfaceDriver::writeRegisters(int servo_id, uint16_t address, uint16_t length, uint8_t *data) const
2047 {
2048  uint8_t error;
2049  int dxl_comm_result;
2050 
2051  // Read address and size always depends on servo series
2052  dxl_comm_result = packetHandler_->writeTxRx(portHandler_.get(), servo_id, address, length, data, &error);
2053 
2054  // check return value
2055  if (dxl_comm_result == COMM_SUCCESS)
2056  {
2057  return true;
2058  }
2059  else
2060  {
2061  return false;
2062  }
2063 }
2064 
2065 // *********************** SYNC_WRITE METHODS *************************** //
2066 
2070 bool DynamixelInterfaceDriver::setMultiPosition(std::unordered_map<int, SyncData> &position_data) const
2071 {
2072  if (position_data.size() == 0)
2073  {
2074  return true;
2075  }
2076 
2077  DynamixelSeriesType type = position_data.begin()->second.type;
2078 
2079  // switch on series type
2080  switch (type)
2081  {
2082  case kSeriesAX:
2083  case kSeriesRX:
2084  case kSeriesDX:
2085  case kSeriesEX:
2086  case kSeriesLegacyMX:
2087  return syncWrite(position_data, kRegLegacy_GoalPosition, 2);
2088  case kSeriesMX:
2089  case kSeriesX:
2090  return syncWrite(position_data, kRegStandard_GoalPosition, 4);
2091  case kSeriesP:
2092  return syncWrite(position_data, kRegP_GoalPosition, 4);
2093  case kSeriesLegacyPro:
2094  return syncWrite(position_data, kRegLegacyPro_GoalPosition, 4);
2095  default:
2096  return false;
2097  }
2098  return false;
2099 }
2100 
2104 bool DynamixelInterfaceDriver::setMultiVelocity(std::unordered_map<int, SyncData> &velocity_data) const
2105 {
2106  if (velocity_data.size() == 0)
2107  {
2108  return true;
2109  }
2110 
2111  DynamixelSeriesType type = velocity_data.begin()->second.type;
2112  // switch on series type
2113  switch (type)
2114  {
2115  case kSeriesAX:
2116  case kSeriesRX:
2117  case kSeriesDX:
2118  case kSeriesEX:
2119  case kSeriesLegacyMX:
2120  return syncWrite(velocity_data, kRegLegacy_MovingSpeed, 2);
2121  case kSeriesMX:
2122  case kSeriesX:
2123  return syncWrite(velocity_data, kRegStandard_GoalVelocity, 4);
2124  case kSeriesP:
2125  return syncWrite(velocity_data, kRegP_GoalVelocity, 4);
2126  case kSeriesLegacyPro:
2127  return syncWrite(velocity_data, kRegLegacyPro_GoalVelocity, 4);
2128  default:
2129  return false;
2130  }
2131  return false;
2132 }
2133 
2137 bool DynamixelInterfaceDriver::setMultiProfileVelocity(std::unordered_map<int, SyncData> &velocity_data) const
2138 {
2139  if (velocity_data.size() == 0)
2140  {
2141  return true;
2142  }
2143 
2144  DynamixelSeriesType type = velocity_data.begin()->second.type;
2145  // switch on series type
2146  switch (type)
2147  {
2148  case kSeriesAX:
2149  case kSeriesRX:
2150  case kSeriesDX:
2151  case kSeriesEX:
2152  case kSeriesLegacyMX:
2153  return syncWrite(velocity_data, kRegLegacy_MovingSpeed, 2);
2154  case kSeriesMX:
2155  case kSeriesX:
2156  return syncWrite(velocity_data, kRegStandard_ProfileVelocity, 4);
2157  case kSeriesP:
2158  return syncWrite(velocity_data, kRegP_ProfileVelocity, 4);
2159  case kSeriesLegacyPro:
2160  return syncWrite(velocity_data, kRegLegacyPro_GoalVelocity, 4);
2161  default:
2162  return false;
2163  }
2164  return false;
2165 }
2166 
2170 bool DynamixelInterfaceDriver::setMultiTorque(std::unordered_map<int, SyncData> &torque_data) const
2171 {
2172  if (torque_data.size() == 0)
2173  {
2174  return true;
2175  }
2176 
2177  DynamixelSeriesType type = torque_data.begin()->second.type;
2178  // switch on series type
2179  switch (type)
2180  {
2181  case kSeriesAX:
2182  case kSeriesRX:
2183  case kSeriesDX:
2184  case kSeriesEX:
2185  return false;
2186  case kSeriesLegacyMX:
2187  return syncWrite(torque_data, kRegLegacy_GoalTorque, 2);
2188  case kSeriesMX:
2189  case kSeriesX:
2190  return syncWrite(torque_data, kRegStandard_GoalCurrent, 2);
2191  case kSeriesP:
2192  return syncWrite(torque_data, kRegP_GoalCurrent, 2);
2193  case kSeriesLegacyPro:
2194  return syncWrite(torque_data, kRegLegacyPro_GoalTorque, 2);
2195  default:
2196  return false;
2197  }
2198  return false;
2199 }
2200 
2201 // ********************** Protected Write Methods *********************** //
2202 
2211 bool DynamixelInterfaceDriver::syncWrite(std::unordered_map<int, SyncData> &write_data, uint16_t address,
2212  uint16_t length) const
2213 {
2214  uint8_t dxl_comm_result;
2215  bool success = true;
2216 
2217  if (use_group_write_)
2218  {
2219  // Initialize GroupSyncWrite instance
2220  dynamixel::GroupSyncWrite groupSyncWrite(portHandler_.get(), packetHandler_.get(), address, length);
2221 
2222  // Add parameters
2223  for (auto &it : write_data)
2224  {
2225  // only write data that matches length
2226  if (it.second.data.size() == length)
2227  {
2228  groupSyncWrite.addParam(it.first, it.second.data.data());
2229  }
2230  }
2231 
2232  // Transmit packet and check success
2233  dxl_comm_result = groupSyncWrite.txPacket();
2234  if (dxl_comm_result != COMM_SUCCESS)
2235  {
2236  return false;
2237  }
2238  else
2239  {
2240  return true;
2241  }
2242  }
2243  else
2244  {
2245  // loop and write to dynamixels
2246  for (auto &it : write_data)
2247  {
2248  if (!writeRegisters(it.first, address, length, it.second.data.data()))
2249  {
2250  success = false;
2251  }
2252  }
2253  return success;
2254  }
2255 }
2256 
2257 } // namespace dynamixel_interface
dynamixel_interface::DynamixelInterfaceDriver::setPositionProportionalGain
bool setPositionProportionalGain(int servo_id, DynamixelSeriesType type, uint16_t gain) const
Definition: dynamixel_interface_driver.cpp:1651
response
const std::string response
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::kRegStandard_GoalVelocity
@ kRegStandard_GoalVelocity
Definition: dynamixel_const.h:218
dynamixel_interface::kRegLegacyPro_PresentPosition
@ kRegLegacyPro_PresentPosition
Definition: dynamixel_const.h:348
dynamixel_interface::kModePositionControl
@ kModePositionControl
Definition: dynamixel_const.h:374
dynamixel_interface::kRegLegacy_TorqueLimit
@ kRegLegacy_TorqueLimit
Definition: dynamixel_const.h:151
dynamixel::GroupBulkRead::getError
bool getError(uint8_t id, uint8_t *error)
dynamixel_interface::kRegP_PositionDGain
@ kRegP_PositionDGain
Definition: dynamixel_const.h:284
dynamixel_interface::kRegLegacyPro_VelocityLimit
@ kRegLegacyPro_VelocityLimit
Definition: dynamixel_const.h:331
dynamixel_interface::DynamixelInterfaceDriver::setMaxTorque
bool setMaxTorque(int servo_id, DynamixelSeriesType type, uint16_t max_torque) const
Definition: dynamixel_interface_driver.cpp:1395
dynamixel_interface::kRegLegacy_GoalPosition
@ kRegLegacy_GoalPosition
Definition: dynamixel_const.h:149
ros::package::getPath
ROSLIB_DECL std::string getPath(const std::string &package_name)
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::kRegP_PositionPGain
@ kRegP_PositionPGain
Definition: dynamixel_const.h:286
dynamixel::GroupSyncRead::addParam
bool addParam(uint8_t id)
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::kRegStandard_VelocityLimit
@ kRegStandard_VelocityLimit
Definition: dynamixel_const.h:194
dynamixel_interface::DynamixelSeriesType
DynamixelSeriesType
Dynamixel types.
Definition: dynamixel_const.h:95
dynamixel_interface::kRegP_DataPort1
@ kRegP_DataPort1
Definition: dynamixel_const.h:307
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::kRegLegacyPro_HardwareErrorStatus
@ kRegLegacyPro_HardwareErrorStatus
Definition: dynamixel_const.h:362
dynamixel_interface::kRegStandard_HardwareErrorStatus
@ kRegStandard_HardwareErrorStatus
Definition: dynamixel_const.h:207
dynamixel_interface::kRegStandard_ProfileVelocity
@ kRegStandard_ProfileVelocity
Definition: dynamixel_const.h:220
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
dynamixel_interface::kRegP_MinPositionLimit
@ kRegP_MinPositionLimit
Definition: dynamixel_const.h:266
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::GroupBulkRead
dynamixel::GroupBulkRead::getData
uint32_t getData(uint8_t id, uint16_t address, uint16_t data_length)
dynamixel_interface::kRegLegacy_GoalTorque
@ kRegLegacy_GoalTorque
Definition: dynamixel_const.h:165
dynamixel_interface::DynamixelSpec::model_number
uint16_t model_number
Model number (e.g 29 = MX-28)
Definition: dynamixel_interface_driver.h:102
dynamixel_interface::kRegStandard_PresentCurrent
@ kRegStandard_PresentCurrent
Definition: dynamixel_const.h:226
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::kRegP_CurrentLimit
@ kRegP_CurrentLimit
Definition: dynamixel_const.h:262
dynamixel_interface::kRegLegacy_CWAngleLimit
@ kRegLegacy_CWAngleLimit
Definition: dynamixel_const.h:121
dynamixel_interface::kModePWMControl
@ kModePWMControl
Definition: dynamixel_const.h:379
dynamixel_interface::DynamixelInterfaceDriver::device_
std::string device_
name of device to open
Definition: dynamixel_interface_driver.h:509
dynamixel_interface_driver.h
Defines the hardware abstraction methods for communicating with dynamixels.
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::kRegStandard_DataPort1
@ kRegStandard_DataPort1
Definition: dynamixel_const.h:233
dynamixel_interface::DynamixelInterfaceDriver::setTorqueEnabled
bool setTorqueEnabled(int servo_id, DynamixelSeriesType type, bool on) const
Definition: dynamixel_interface_driver.cpp:1498
dynamixel_interface::kRegP_VelocityIGain
@ kRegP_VelocityIGain
Definition: dynamixel_const.h:282
dynamixel_interface::DynamixelInterfaceDriver::setOperatingMode
bool setOperatingMode(int servo_id, DynamixelSeriesType type, DynamixelControlMode operating_mode) const
Definition: dynamixel_interface_driver.cpp:1185
dynamixel_interface::kModeVelocityControl
@ kModeVelocityControl
Definition: dynamixel_const.h:373
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::kRegStandard_GoalCurrent
@ kRegStandard_GoalCurrent
Definition: dynamixel_const.h:217
dynamixel_interface::kRegLegacyPro_MinAngleLimit
@ kRegLegacyPro_MinAngleLimit
Definition: dynamixel_const.h:334
dynamixel_interface::kRegP_VelocityLimit
@ kRegP_VelocityLimit
Definition: dynamixel_const.h:264
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::kRegStandard_PositionIGain
@ kRegStandard_PositionIGain
Definition: dynamixel_const.h:211
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::kRegLegacy_PresentVoltage
@ kRegLegacy_PresentVoltage
Definition: dynamixel_const.h:155
dynamixel_interface::kRegLegacy_PresentPosition
@ kRegLegacy_PresentPosition
Definition: dynamixel_const.h:152
dynamixel_interface::kRegLegacyPro_GoalTorque
@ kRegLegacyPro_GoalTorque
Definition: dynamixel_const.h:347
dynamixel_interface::kRegStandard_GoalPosition
@ kRegStandard_GoalPosition
Definition: dynamixel_const.h:221
dynamixel_interface::kSeriesRX
@ kSeriesRX
Definition: dynamixel_const.h:98
dynamixel_interface::kRegLegacy_DGain
@ kRegLegacy_DGain
Definition: dynamixel_const.h:139
dynamixel_interface::kRegP_TorqueEnable
@ kRegP_TorqueEnable
Definition: dynamixel_const.h:275
dynamixel::GroupSyncWrite::addParam
bool addParam(uint8_t id, uint8_t *data)
dynamixel_interface::kRegStandard_VelocityPGain
@ kRegStandard_VelocityPGain
Definition: dynamixel_const.h:209
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::kSeriesEX
@ kSeriesEX
Definition: dynamixel_const.h:100
dynamixel_interface::kRegStandard_MaxPositionLimit
@ kRegStandard_MaxPositionLimit
Definition: dynamixel_const.h:195
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::PacketHandler::getPacketHandler
static PacketHandler * getPacketHandler(float protocol_version=2.0)
dynamixel_interface::kRegLegacy_IGain
@ kRegLegacy_IGain
Definition: dynamixel_const.h:140
dynamixel_interface::kRegP_OperatingMode
@ kRegP_OperatingMode
Definition: dynamixel_const.h:253
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::GroupSyncWrite::txPacket
int txPacket()
dynamixel_interface::kRegLegacy_CCWAngleLimit
@ kRegLegacy_CCWAngleLimit
Definition: dynamixel_const.h:122
COMM_SUCCESS
int COMM_SUCCESS
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::kRegP_PresentCurrent
@ kRegP_PresentCurrent
Definition: dynamixel_const.h:300
dynamixel_interface::kSeriesUnknown
@ kSeriesUnknown
Definition: dynamixel_const.h:106
dynamixel_interface::kRegLegacyPro_MaxTorque
@ kRegLegacyPro_MaxTorque
Definition: dynamixel_const.h:332
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::kRegStandard_TorqueEnable
@ kRegStandard_TorqueEnable
Definition: dynamixel_const.h:203
dynamixel_interface::kRegLegacy_TorqueControlEnable
@ kRegLegacy_TorqueControlEnable
Definition: dynamixel_const.h:164
dynamixel_interface::DynamixelInterfaceDriver::getErrorStatus
bool getErrorStatus(int servo_id, DynamixelSeriesType type, uint8_t *error) const
Definition: dynamixel_interface_driver.cpp:342
dynamixel::GroupSyncRead::getError
bool getError(uint8_t id, uint8_t *error)
dynamixel_interface::DynamixelInterfaceDriver::setTorque
bool setTorque(int servo_id, DynamixelSeriesType type, int16_t torque) const
Definition: dynamixel_interface_driver.cpp:1994
dynamixel_interface::kRegStandard_PresentInputVoltage
@ kRegStandard_PresentInputVoltage
Definition: dynamixel_const.h:231
dynamixel_interface::kRegLegacyPro_TorqueEnable
@ kRegLegacyPro_TorqueEnable
Definition: dynamixel_const.h:344
dynamixel_interface::kRegP_GoalPosition
@ kRegP_GoalPosition
Definition: dynamixel_const.h:295
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::kRegP_HardwareErrorStatus
@ kRegP_HardwareErrorStatus
Definition: dynamixel_const.h:281
dynamixel_interface::kModeCurrentBasedPositionControl
@ kModeCurrentBasedPositionControl
Definition: dynamixel_const.h:377
dynamixel_interface::kRegLegacyPro_MaxAngleLimit
@ kRegLegacyPro_MaxAngleLimit
Definition: dynamixel_const.h:333
dynamixel_interface::kRegStandard_OperatingMode
@ kRegStandard_OperatingMode
Definition: dynamixel_const.h:183
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::kRegP_PresentInputVoltage
@ kRegP_PresentInputVoltage
Definition: dynamixel_const.h:305
dynamixel::PortHandler::getPortHandler
static PortHandler * getPortHandler(const char *port_name)
dynamixel_interface::kRegLegacyPro_DataPort1
@ kRegLegacyPro_DataPort1
Definition: dynamixel_const.h:354
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::kRegLegacyPro_GoalPosition
@ kRegLegacyPro_GoalPosition
Definition: dynamixel_const.h:345
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::kRegLegacy_MovingSpeed
@ kRegLegacy_MovingSpeed
Definition: dynamixel_const.h:150
package.h
dynamixel_interface::DynamixelInterfaceDriver::setMultiTorque
bool setMultiTorque(std::unordered_map< int, SyncData > &torque_data) const
Definition: dynamixel_interface_driver.cpp:2170
dynamixel_interface::kRegLegacyPro_PresentVoltage
@ kRegLegacyPro_PresentVoltage
Definition: dynamixel_const.h:351
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::DynamixelInterfaceDriver::ping
bool ping(int servo_id) const
Definition: dynamixel_interface_driver.cpp:295
dynamixel_interface::kRegP_ProfileVelocity
@ kRegP_ProfileVelocity
Definition: dynamixel_const.h:294
dynamixel_interface::kRegStandard_PositionPGain
@ kRegStandard_PositionPGain
Definition: dynamixel_const.h:212
dynamixel_interface::kRegLegacyPro_OperatingMode
@ kRegLegacyPro_OperatingMode
Definition: dynamixel_const.h:325
dynamixel_interface::kRegLegacyPro_PositionPGain
@ kRegLegacyPro_PositionPGain
Definition: dynamixel_const.h:343
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::kRegStandard_VelocityIGain
@ kRegStandard_VelocityIGain
Definition: dynamixel_const.h:208
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::kRegP_PositionIGain
@ kRegP_PositionIGain
Definition: dynamixel_const.h:285
dynamixel_interface::kRegLegacy_MaxTorque
@ kRegLegacy_MaxTorque
Definition: dynamixel_const.h:127
dynamixel::GroupSyncWrite
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
ROS_ERROR
#define ROS_ERROR(...)
dynamixel_interface::DynamixelInterfaceDriver::setMultiVelocity
bool setMultiVelocity(std::unordered_map< int, SyncData > &velocity_data) const
Definition: dynamixel_interface_driver.cpp:2104
dynamixel::GroupSyncRead::txRxPacket
int txRxPacket()
dynamixel_interface::kSeriesLegacyPro
@ kSeriesLegacyPro
Definition: dynamixel_const.h:104
dynamixel_interface::kRegLegacy_TorqueEnable
@ kRegLegacy_TorqueEnable
Definition: dynamixel_const.h:135
dynamixel_interface::kRegP_GoalCurrent
@ kRegP_GoalCurrent
Definition: dynamixel_const.h:291
dynamixel_interface::kRegP_GoalVelocity
@ kRegP_GoalVelocity
Definition: dynamixel_const.h:292
dynamixel_interface::DynamixelSpec::encoder_range_deg
double encoder_range_deg
Motor encoder range in degrees.
Definition: dynamixel_interface_driver.h:106
dynamixel_interface::DynamixelInterfaceDriver::getMaxTorque
bool getMaxTorque(int servo_id, DynamixelSeriesType type, uint16_t *max_torque) const
Definition: dynamixel_interface_driver.cpp:392
dynamixel_interface::kRegStandard_CurrentLimit
@ kRegStandard_CurrentLimit
Definition: dynamixel_const.h:192
dynamixel::GroupSyncRead
dynamixel_interface::kRegStandard_MinPositionLimit
@ kRegStandard_MinPositionLimit
Definition: dynamixel_const.h:196
dynamixel_interface::kRegLegacy_PGain
@ kRegLegacy_PGain
Definition: dynamixel_const.h:141
dynamixel::GroupBulkRead::txRxPacket
int txRxPacket()
dynamixel::GroupSyncRead::getData
uint32_t getData(uint8_t id, uint16_t address, uint16_t data_length)
dynamixel_interface::kModeTorqueControl
@ kModeTorqueControl
Definition: dynamixel_const.h:372
ROS_INFO
#define ROS_INFO(...)
dynamixel_interface::kRegLegacyPro_GoalVelocity
@ kRegLegacyPro_GoalVelocity
Definition: dynamixel_const.h:346
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::kRegP_MaxPositionLimit
@ kRegP_MaxPositionLimit
Definition: dynamixel_const.h:265
dynamixel::GroupBulkRead::addParam
bool addParam(uint8_t id, uint16_t start_address, uint16_t data_length)
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::kRegP_VelocityPGain
@ kRegP_VelocityPGain
Definition: dynamixel_const.h:283
dynamixel_interface::kRegStandard_PositionDGain
@ kRegStandard_PositionDGain
Definition: dynamixel_const.h:210
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::kRegLegacyPro_VelocityIGain
@ kRegLegacyPro_VelocityIGain
Definition: dynamixel_const.h:341
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::GroupSyncRead::isAvailable
bool isAvailable(uint8_t id, uint16_t address, uint16_t data_length)
dynamixel_interface::kRegLegacyPro_VelocityPGain
@ kRegLegacyPro_VelocityPGain
Definition: dynamixel_const.h:342
dynamixel::GroupBulkRead::isAvailable
bool isAvailable(uint8_t id, uint16_t address, uint16_t data_length)
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