dynamixel.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /* Authors: Darby Lim, Hye-Jong KIM, Ryan Shim, Yong-Ho Na */
18 
19 #include "../include/open_manipulator_libs/dynamixel.h"
20 
21 using namespace dynamixel;
22 using namespace robotis_manipulator;
23 
24 /*****************************************************************************
25 ** Joint Dynamixel Control Functions
26 *****************************************************************************/
27 void JointDynamixel::init(std::vector<uint8_t> actuator_id, const void *arg)
28 {
29  STRING *get_arg_ = (STRING *)arg;
30 
31  bool result = JointDynamixel::initialize(actuator_id ,get_arg_[0], get_arg_[1]);
32 
33  if (result == false)
34  return;
35 }
36 
37 void JointDynamixel::setMode(std::vector<uint8_t> actuator_id, const void *arg)
38 {
39  bool result = false;
40  // const char* log = NULL;
41 
42  STRING *get_arg_ = (STRING *)arg;
43 
44  if (get_arg_[0] == "position_mode" || get_arg_[0] == "current_based_position_mode")
45  {
46  result = JointDynamixel::setOperatingMode(actuator_id, get_arg_[0]);
47  if (result == false)
48  return;
49 
50  result = JointDynamixel::setSDKHandler(actuator_id.at(0));
51  if (result == false)
52  return;
53  }
54  else
55  {
56  result = JointDynamixel::writeProfileValue(actuator_id, get_arg_[0], std::atoi(get_arg_[1].c_str()));
57  if (result == false)
58  return;
59  }
60  return;
61 }
62 
63 std::vector<uint8_t> JointDynamixel::getId()
64 {
65  return dynamixel_.id;
66 }
67 
69 {
70  const char* log = NULL;
71  bool result = false;
72 
73  for (uint32_t index = 0; index < dynamixel_.num; index++)
74  {
75  result = dynamixel_workbench_->torqueOn(dynamixel_.id.at(index), &log);
76  if (result == false)
77  {
78  log::error(log);
79  }
80  }
81  enabled_state_ = true;
82 }
83 
85 {
86  const char* log = NULL;
87  bool result = false;
88 
89  for (uint32_t index = 0; index < dynamixel_.num; index++)
90  {
91  result = dynamixel_workbench_->torqueOff(dynamixel_.id.at(index), &log);
92  if (result == false)
93  {
94  log::error(log);
95  }
96  }
97  enabled_state_ = false;
98 }
99 
100 bool JointDynamixel::sendJointActuatorValue(std::vector<uint8_t> actuator_id, std::vector<robotis_manipulator::ActuatorValue> value_vector)
101 {
102  bool result = false;
103 
104  std::vector<double> radian_vector;
105  for(uint32_t index = 0; index < value_vector.size(); index++)
106  {
107  radian_vector.push_back(value_vector.at(index).position);
108  }
109  result = JointDynamixel::writeGoalPosition(actuator_id, radian_vector);
110  if (result == false)
111  return false;
112 
113  return true;
114 }
115 
116 std::vector<robotis_manipulator::ActuatorValue> JointDynamixel::receiveJointActuatorValue(std::vector<uint8_t> actuator_id)
117 {
118  return JointDynamixel::receiveAllDynamixelValue(actuator_id);
119 }
120 
121 
122 /*****************************************************************************
123 ** Functions called in Joint Dynamixel Control Functions
124 *****************************************************************************/
125 bool JointDynamixel::initialize(std::vector<uint8_t> actuator_id, STRING dxl_device_name, STRING dxl_baud_rate)
126 {
127  bool result = false;
128  const char* log = NULL;
129 
130  STRING return_delay_time_st = "Return_Delay_Time";
131  const char * return_delay_time_char = return_delay_time_st.c_str();
132 
133  dynamixel_.id = actuator_id;
134  dynamixel_.num = actuator_id.size();
135 
136  dynamixel_workbench_ = new DynamixelWorkbench;
137 
138  result = dynamixel_workbench_->init(dxl_device_name.c_str(), std::atoi(dxl_baud_rate.c_str()), &log);
139  if (result == false)
140  {
141  log::error(log);
142  }
143 
144  uint16_t get_model_number;
145  for (uint8_t index = 0; index < dynamixel_.num; index++)
146  {
147  uint8_t id = dynamixel_.id.at(index);
148  result = dynamixel_workbench_->ping(id, &get_model_number, &log);
149 
150  if (result == false)
151  {
152  log::error(log);
153  log::error("Please check your Dynamixel ID");
154  }
155  else
156  {
157  char str[100];
158  sprintf(str, "Joint Dynamixel ID : %d, Model Name : %s", id, dynamixel_workbench_->getModelName(id));
159  log::println(str);
160 
161  result = dynamixel_workbench_->setVelocityBasedProfile(id, &log);
162  if(result == false)
163  {
164  log::error(log);
165  log::error("Please check your Dynamixel firmware version (v38~)");
166  }
167 
168  result = dynamixel_workbench_->writeRegister(id, return_delay_time_char, 0, &log);
169  if (result == false)
170  {
171  log::error(log);
172  log::error("Please check your Dynamixel firmware version");
173  }
174  }
175  }
176  return true;
177 }
178 
179 bool JointDynamixel::setOperatingMode(std::vector<uint8_t> actuator_id, STRING dynamixel_mode)
180 {
181  const char* log = NULL;
182  bool result = false;
183 
184  const uint32_t velocity = 0;
185  const uint32_t acceleration = 0;
186  const uint32_t current = 0;
187 
188  if (dynamixel_mode == "position_mode")
189  {
190  for (uint8_t num = 0; num < actuator_id.size(); num++)
191  {
192  result = dynamixel_workbench_->jointMode(actuator_id.at(num), velocity, acceleration, &log);
193  if (result == false)
194  {
195  log::error(log);
196  }
197  }
198  }
199  else if (dynamixel_mode == "current_based_position_mode")
200  {
201  for (uint8_t num = 0; num < actuator_id.size(); num++)
202  {
203  result = dynamixel_workbench_->currentBasedPositionMode(actuator_id.at(num), current, &log);
204  if (result == false)
205  {
206  log::error(log);
207  }
208  }
209  }
210  else
211  {
212  for (uint8_t num = 0; num < actuator_id.size(); num++)
213  {
214  result = dynamixel_workbench_->jointMode(actuator_id.at(num), velocity, acceleration, &log);
215  if (result == false)
216  {
217  log::error(log);
218  }
219  }
220  }
221 
222  return true;
223 }
224 
225 bool JointDynamixel::setSDKHandler(uint8_t actuator_id)
226 {
227  bool result = false;
228  const char* log = NULL;
229 
230  result = dynamixel_workbench_->addSyncWriteHandler(actuator_id, "Goal_Position", &log);
231  if (result == false)
232  {
233  log::error(log);
234  }
235 
236  result = dynamixel_workbench_->addSyncReadHandler(ADDR_PRESENT_CURRENT_2,
238  &log);
239  if (result == false)
240  {
241  log::error(log);
242  }
243 
244  return true;
245 }
246 
247 bool JointDynamixel::writeProfileValue(std::vector<uint8_t> actuator_id, STRING profile_mode, uint32_t value)
248 {
249  const char* log = NULL;
250  bool result = false;
251 
252  const char * char_profile_mode = profile_mode.c_str();
253 
254  for (uint8_t num = 0; num < actuator_id.size(); num++)
255  {
256  result = dynamixel_workbench_->writeRegister(actuator_id.at(num), char_profile_mode, value, &log);
257  if (result == false)
258  {
259  log::error(log);
260  }
261  }
262 
263  return true;
264 }
265 
266 bool JointDynamixel::writeGoalPosition(std::vector<uint8_t> actuator_id, std::vector<double> radian_vector)
267 {
268  bool result = false;
269  const char* log = NULL;
270 
271  uint8_t id_array[actuator_id.size()];
272  int32_t goal_position[actuator_id.size()];
273 
274  for (uint8_t index = 0; index < actuator_id.size(); index++)
275  {
276  id_array[index] = actuator_id.at(index);
277  goal_position[index] = dynamixel_workbench_->convertRadian2Value(actuator_id.at(index), radian_vector.at(index));
278  }
279 
280  result = dynamixel_workbench_->syncWrite(SYNC_WRITE_HANDLER, id_array, actuator_id.size(), goal_position, 1, &log);
281  if (result == false)
282  {
283  log::error(log);
284  }
285 
286  return true;
287 }
288 
289 std::vector<robotis_manipulator::ActuatorValue> JointDynamixel::receiveAllDynamixelValue(std::vector<uint8_t> actuator_id)
290 {
291  bool result = false;
292  const char* log = NULL;
293 
294  std::vector<robotis_manipulator::ActuatorValue> all_actuator;
295 
296  uint8_t id_array[actuator_id.size()];
297  for (uint8_t index = 0; index < actuator_id.size(); index++)
298  id_array[index] = actuator_id.at(index);
299 
300  int32_t get_current[actuator_id.size()];
301  int32_t get_velocity[actuator_id.size()];
302  int32_t get_position[actuator_id.size()];
303 
304  result = dynamixel_workbench_->syncRead(SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT,
305  id_array,
306  actuator_id.size(),
307  &log);
308  if (result == false)
309  {
310  log::error(log);
311  }
312 
313  result = dynamixel_workbench_->getSyncReadData(SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT,
314  id_array,
315  actuator_id.size(),
318  get_current,
319  &log);
320  if (result == false)
321  {
322  log::error(log);
323  }
324 
325  result = dynamixel_workbench_->getSyncReadData(SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT,
326  id_array,
327  actuator_id.size(),
330  get_velocity,
331  &log);
332  if (result == false)
333  {
334  log::error(log);
335  }
336 
337  result = dynamixel_workbench_->getSyncReadData(SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT,
338  id_array,
339  actuator_id.size(),
342  get_position,
343  &log);
344  if (result == false)
345  {
346  log::error(log);
347  }
348 
349  for (uint8_t index = 0; index < actuator_id.size(); index++)
350  {
352  actuator.effort = dynamixel_workbench_->convertValue2Current(get_current[index]);
353  actuator.velocity = dynamixel_workbench_->convertValue2Velocity(actuator_id.at(index), get_velocity[index]);
354  actuator.position = dynamixel_workbench_->convertValue2Radian(actuator_id.at(index), get_position[index]);
355 
356  all_actuator.push_back(actuator);
357  }
358 
359  return all_actuator;
360 }
361 
362 
363 /*****************************************************************************
364 ** Joint Dynamixel Profile Control Functions
365 *****************************************************************************/
367 {
368  control_loop_time_ = control_loop_time;
369 }
370 
371 void JointDynamixelProfileControl::init(std::vector<uint8_t> actuator_id, const void *arg)
372 {
373  STRING *get_arg_ = (STRING *)arg;
374 
375  bool result = JointDynamixelProfileControl::initialize(actuator_id ,get_arg_[0], get_arg_[1]);
376 
377  if (result == false)
378  return;
379 }
380 
381 void JointDynamixelProfileControl::setMode(std::vector<uint8_t> actuator_id, const void *arg)
382 {
383  bool result = false;
384  // const char* log = NULL;
385 
386  STRING *get_arg_ = (STRING *)arg;
387 
388  if (get_arg_[0] == "position_mode" || get_arg_[0] == "current_based_position_mode")
389  {
390  result = JointDynamixelProfileControl::setOperatingMode(actuator_id, get_arg_[0]);
391  if (result == false)
392  return;
393 
394  result = JointDynamixelProfileControl::setSDKHandler(actuator_id.at(0));
395  if (result == false)
396  return;
397  }
398  else
399  {
400  result = JointDynamixelProfileControl::writeProfileValue(actuator_id, get_arg_[0], std::atoi(get_arg_[1].c_str()));
401  if (result == false)
402  return;
403  }
404  return;
405 }
406 
408 {
409  return dynamixel_.id;
410 }
411 
413 {
414  const char* log = NULL;
415  bool result = false;
416 
417  for (uint32_t index = 0; index < dynamixel_.num; index++)
418  {
419  result = dynamixel_workbench_->torqueOn(dynamixel_.id.at(index), &log);
420  if (result == false)
421  {
422  log::error(log);
423  }
424  }
425  enabled_state_ = true;
426 }
427 
429 {
430  const char* log = NULL;
431  bool result = false;
432 
433  for (uint32_t index = 0; index < dynamixel_.num; index++)
434  {
435  result = dynamixel_workbench_->torqueOff(dynamixel_.id.at(index), &log);
436  if (result == false)
437  {
438  log::error(log);
439  }
440  }
441  enabled_state_ = false;
442 }
443 
444 bool JointDynamixelProfileControl::sendJointActuatorValue(std::vector<uint8_t> actuator_id, std::vector<robotis_manipulator::ActuatorValue> value_vector)
445 {
446  bool result = false;
447 
448  result = JointDynamixelProfileControl::writeGoalProfilingControlValue(actuator_id, value_vector);
449  if (result == false)
450  return false;
451 
452  return true;
453 }
454 
455 std::vector<robotis_manipulator::ActuatorValue> JointDynamixelProfileControl::receiveJointActuatorValue(std::vector<uint8_t> actuator_id)
456 {
458 }
459 
460 
461 /*****************************************************************************
462 ** Functions called in Joint Dynamixel Profile Control Functions
463 *****************************************************************************/
464 bool JointDynamixelProfileControl::initialize(std::vector<uint8_t> actuator_id, STRING dxl_device_name, STRING dxl_baud_rate)
465 {
466  bool result = false;
467  const char* log = NULL;
468 
469  STRING return_delay_time_st = "Return_Delay_Time";
470  const char * return_delay_time_char = return_delay_time_st.c_str();
471 
472  dynamixel_.id = actuator_id;
473  dynamixel_.num = actuator_id.size();
474 
475  dynamixel_workbench_ = new DynamixelWorkbench;
476 
477  result = dynamixel_workbench_->init(dxl_device_name.c_str(), std::atoi(dxl_baud_rate.c_str()), &log);
478  if (result == false)
479  {
480  log::error(log);
481  }
482 
483  uint16_t get_model_number;
484  for (uint8_t index = 0; index < dynamixel_.num; index++)
485  {
486  uint8_t id = dynamixel_.id.at(index);
487  result = dynamixel_workbench_->ping(id, &get_model_number, &log);
488 
489  if (result == false)
490  {
491  log::error(log);
492  log::error("Please check your Dynamixel ID");
493  }
494  else
495  {
496  char str[100];
497  sprintf(str, "Joint Dynamixel ID : %d, Model Name : %s", id, dynamixel_workbench_->getModelName(id));
498  log::println(str);
499 
500  result = dynamixel_workbench_->setTimeBasedProfile(id, &log);
501  if(result == false)
502  {
503  log::error(log);
504  log::error("Please check your Dynamixel firmware version (v38~)");
505  }
506 
507  result = dynamixel_workbench_->writeRegister(id, return_delay_time_char, 0, &log);
508  if (result == false)
509  {
510  log::error(log);
511  log::error("Please check your Dynamixel firmware version");
512  }
513  }
514  }
515  return true;
516 }
517 
518 bool JointDynamixelProfileControl::setOperatingMode(std::vector<uint8_t> actuator_id, STRING dynamixel_mode)
519 {
520  const char* log = NULL;
521  bool result = false;
522 
523  const uint32_t velocity = uint32_t(control_loop_time_*1000) * 3;
524  const uint32_t acceleration = uint32_t(control_loop_time_*1000);
525  const uint32_t current = 0;
526 
527  if (dynamixel_mode == "position_mode")
528  {
529  for (uint8_t num = 0; num < actuator_id.size(); num++)
530  {
531  result = dynamixel_workbench_->jointMode(actuator_id.at(num), velocity, acceleration, &log);
532  if (result == false)
533  {
534  log::error(log);
535  }
536  }
537  }
538  else if (dynamixel_mode == "current_based_position_mode")
539  {
540  for (uint8_t num = 0; num < actuator_id.size(); num++)
541  {
542  result = dynamixel_workbench_->currentBasedPositionMode(actuator_id.at(num), current, &log);
543  if (result == false)
544  {
545  log::error(log);
546  }
547  }
548  }
549  else
550  {
551  for (uint8_t num = 0; num < actuator_id.size(); num++)
552  {
553  result = dynamixel_workbench_->jointMode(actuator_id.at(num), velocity, acceleration, &log);
554  if (result == false)
555  {
556  log::error(log);
557  }
558  }
559  }
560 
561  return true;
562 }
563 
565 {
566  bool result = false;
567  const char* log = NULL;
568 
569  result = dynamixel_workbench_->addSyncWriteHandler(actuator_id, "Goal_Position", &log);
570  if (result == false)
571  {
572  log::error(log);
573  }
574 
575  result = dynamixel_workbench_->addSyncReadHandler(ADDR_PRESENT_CURRENT_2,
577  &log);
578  if (result == false)
579  {
580  log::error(log);
581  }
582 
583  return true;
584 }
585 
586 bool JointDynamixelProfileControl::writeProfileValue(std::vector<uint8_t> actuator_id, STRING profile_mode, uint32_t value)
587 {
588  const char* log = NULL;
589  bool result = false;
590 
591  const char * char_profile_mode = profile_mode.c_str();
592 
593  for (uint8_t num = 0; num < actuator_id.size(); num++)
594  {
595  result = dynamixel_workbench_->writeRegister(actuator_id.at(num), char_profile_mode, value, &log);
596  if (result == false)
597  {
598  log::error(log);
599  }
600  }
601  return true;
602 }
603 
604 bool JointDynamixelProfileControl::writeGoalProfilingControlValue(std::vector<uint8_t> actuator_id, std::vector<robotis_manipulator::ActuatorValue> value_vector)
605 {
606  bool result = false;
607  const char* log = NULL;
608 
609  uint8_t id_array[actuator_id.size()];
610  int32_t goal_value[actuator_id.size()];
611 
612  //add tarajectory eq.
613  for(uint8_t index = 0; index < actuator_id.size(); index++)
614  {
615  float result_position;
616  float time_control = control_loop_time_; //ms
617 
618  if(previous_goal_value_.find(actuator_id.at(index)) == previous_goal_value_.end())
619  {
620  previous_goal_value_.insert(std::make_pair(actuator_id.at(index), value_vector.at(index)));
621  }
622 
623  result_position = value_vector.at(index).position + 3*(value_vector.at(index).velocity * (time_control))/2;
624 
625  id_array[index] = actuator_id.at(index);
626  goal_value[index] = dynamixel_workbench_->convertRadian2Value(actuator_id.at(index), result_position);
627 
628  previous_goal_value_[actuator_id.at(index)] = value_vector.at(index);
629  }
630 
631  result = dynamixel_workbench_->syncWrite(SYNC_WRITE_HANDLER, id_array, actuator_id.size(), goal_value, 1, &log);
632  if (result == false)
633  {
634  log::error(log);
635  }
636  return true;
637 }
638 
639 std::vector<robotis_manipulator::ActuatorValue> JointDynamixelProfileControl::receiveAllDynamixelValue(std::vector<uint8_t> actuator_id)
640 {
641  bool result = false;
642  const char* log = NULL;
643 
644  std::vector<robotis_manipulator::ActuatorValue> all_actuator;
645 
646  uint8_t id_array[actuator_id.size()];
647  for (uint8_t index = 0; index < actuator_id.size(); index++)
648  id_array[index] = actuator_id.at(index);
649 
650  int32_t get_current[actuator_id.size()];
651  int32_t get_velocity[actuator_id.size()];
652  int32_t get_position[actuator_id.size()];
653 
654  result = dynamixel_workbench_->syncRead(SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT,
655  id_array,
656  actuator_id.size(),
657  &log);
658  if (result == false)
659  {
660  log::error(log);
661  }
662 
663  result = dynamixel_workbench_->getSyncReadData(SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT,
664  id_array,
665  actuator_id.size(),
668  get_current,
669  &log);
670  if (result == false)
671  {
672  log::error(log);
673  }
674 
675  result = dynamixel_workbench_->getSyncReadData(SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT,
676  id_array,
677  actuator_id.size(),
680  get_velocity,
681  &log);
682  if (result == false)
683  {
684  log::error(log);
685  }
686 
687  result = dynamixel_workbench_->getSyncReadData(SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT,
688  id_array,
689  actuator_id.size(),
692  get_position,
693  &log);
694  if (result == false)
695  {
696  log::error(log);
697  }
698 
699  for (uint8_t index = 0; index < actuator_id.size(); index++)
700  {
702  actuator.effort = dynamixel_workbench_->convertValue2Current(get_current[index]);
703  actuator.velocity = dynamixel_workbench_->convertValue2Velocity(actuator_id.at(index), get_velocity[index]);
704  actuator.position = dynamixel_workbench_->convertValue2Radian(actuator_id.at(index), get_position[index]);
705 
706  all_actuator.push_back(actuator);
707  }
708 
709  return all_actuator;
710 }
711 
712 
713 /*****************************************************************************
714 ** Tool Dynamixel Control Functions
715 *****************************************************************************/
716 void GripperDynamixel::init(uint8_t actuator_id, const void *arg)
717 {
718  STRING *get_arg_ = (STRING *)arg;
719 
720  bool result = GripperDynamixel::initialize(actuator_id ,get_arg_[0], get_arg_[1]);
721 
722  if (result == false)
723  return;
724 }
725 
726 void GripperDynamixel::setMode(const void *arg)
727 {
728  bool result = false;
729 // const char* log = NULL;
730 
731  STRING *get_arg_ = (STRING *)arg;
732 
733  if (get_arg_[0] == "position_mode" || get_arg_[0] == "current_based_position_mode")
734  {
735  result = GripperDynamixel::setOperatingMode(get_arg_[0]);
736  if (result == false)
737  return;
738  }
739  else
740  {
741  result = GripperDynamixel::writeProfileValue(get_arg_[0], std::atoi(get_arg_[1].c_str()));
742  if (result == false)
743  return;
744  }
745 
747  if (result == false)
748  return;
749 }
750 
752 {
753  return dynamixel_.id.at(0);
754 }
755 
757 {
758  const char* log = NULL;
759  bool result = false;
760 
761  result = dynamixel_workbench_->torqueOn(dynamixel_.id.at(0), &log);
762  if (result == false)
763  {
764  log::error(log);
765  }
766  enabled_state_ = true;
767 }
768 
770 {
771  const char* log = NULL;
772  bool result = false;
773 
774  result = dynamixel_workbench_->torqueOff(dynamixel_.id.at(0), &log);
775  if (result == false)
776  {
777  log::error(log);
778  }
779  enabled_state_ = false;
780 }
781 
783 {
785 }
786 
788 {
791  result.velocity = 0.0;
792  result.acceleration = 0.0;
793  result.effort = 0.0;
794  return result;
795 }
796 
797 
798 /*****************************************************************************
799 ** Functions called in Tool Dynamixel Profile Control Functions
800 *****************************************************************************/
801 bool GripperDynamixel::initialize(uint8_t actuator_id, STRING dxl_device_name, STRING dxl_baud_rate)
802 {
803  const char* log = NULL;
804  bool result = false;
805 
806  STRING return_delay_time_st = "Return_Delay_Time";
807  const char * return_delay_time_char = return_delay_time_st.c_str();
808 
809  dynamixel_.id.push_back(actuator_id);
810  dynamixel_.num = 1;
811 
812  dynamixel_workbench_ = new DynamixelWorkbench;
813 
814  result = dynamixel_workbench_->init(dxl_device_name.c_str(), std::atoi(dxl_baud_rate.c_str()), &log);
815  if (result == false)
816  {
817  log::error(log);
818  }
819 
820  uint16_t get_model_number;
821  result = dynamixel_workbench_->ping(dynamixel_.id.at(0), &get_model_number, &log);
822  if (result == false)
823  {
824  log::error(log);
825  log::error("Please check your Dynamixel ID");
826  }
827  else
828  {
829  char str[100];
830  sprintf(str, "Gripper Dynamixel ID : %d, Model Name :", dynamixel_.id.at(0));
831  strcat(str, dynamixel_workbench_->getModelName(dynamixel_.id.at(0)));
832  log::println(str);
833 
834  result = dynamixel_workbench_->setVelocityBasedProfile(dynamixel_.id.at(0), &log);
835  if(result == false)
836  {
837  log::error(log);
838  log::error("Please check your Dynamixel firmware version (v38~)");
839  }
840 
841  result = dynamixel_workbench_->writeRegister(dynamixel_.id.at(0), return_delay_time_char, 0, &log);
842  if (result == false)
843  {
844  log::error(log);
845  log::error("Please check your Dynamixel firmware version");
846  }
847  }
848 
849  return true;
850 }
851 
853 {
854  const char* log = NULL;
855  bool result = false;
856 
857  const uint32_t velocity = 0;
858  const uint32_t acceleration = 0;
859  const uint32_t current = 200;
860 
861  if (dynamixel_mode == "position_mode")
862  {
863  result = dynamixel_workbench_->jointMode(dynamixel_.id.at(0), velocity, acceleration, &log);
864  if (result == false)
865  {
866  log::error(log);
867  }
868  }
869  else if (dynamixel_mode == "current_based_position_mode")
870  {
871  result = dynamixel_workbench_->currentBasedPositionMode(dynamixel_.id.at(0), current, &log);
872  if (result == false)
873  {
874  log::error(log);
875  }
876  }
877  else
878  {
879  result = dynamixel_workbench_->jointMode(dynamixel_.id.at(0), velocity, acceleration, &log);
880  if (result == false)
881  {
882  log::error(log);
883  }
884  }
885 
886  return true;
887 }
888 
889 bool GripperDynamixel::writeProfileValue(STRING profile_mode, uint32_t value)
890 {
891  const char* log = NULL;
892  bool result = false;
893 
894  const char * char_profile_mode = profile_mode.c_str();
895 
896  result = dynamixel_workbench_->writeRegister(dynamixel_.id.at(0), char_profile_mode, value, &log);
897  if (result == false)
898  {
899  log::error(log);
900  }
901 
902  return true;
903 }
904 
906 {
907  bool result = false;
908  const char* log = NULL;
909 
910  result = dynamixel_workbench_->addSyncWriteHandler(dynamixel_.id.at(0), "Goal_Position", &log);
911  if (result == false)
912  {
913  log::error(log);
914  }
915 
916  result = dynamixel_workbench_->addSyncReadHandler(dynamixel_.id.at(0),
917  "Present_Position",
918  &log);
919  if (result == false)
920  {
921  log::error(log);
922  }
923 
924  return true;
925 }
926 
928 {
929  bool result = false;
930  const char* log = NULL;
931 
932  int32_t goal_position = 0;
933 
934  goal_position = dynamixel_workbench_->convertRadian2Value(dynamixel_.id.at(0), radian);
935 
936  result = dynamixel_workbench_->syncWrite(SYNC_WRITE_HANDLER, &goal_position, &log);
937  if (result == false)
938  {
939  log::error(log);
940  }
941 
942  return true;
943 }
944 
946 {
947  bool result = false;
948  const char* log = NULL;
949 
950  int32_t get_value = 0;
951  uint8_t id_array[1] = {dynamixel_.id.at(0)};
952 
953  result = dynamixel_workbench_->syncRead(SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT,
954  id_array,
955  (uint8_t)1,
956  &log);
957  if (result == false)
958  {
959  log::error(log);
960  }
961 
962  result = dynamixel_workbench_->getSyncReadData(SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT,
963  id_array,
964  (uint8_t)1,
965  &get_value,
966  &log);
967  if (result == false)
968  {
969  log::error(log);
970  }
971 
972  return dynamixel_workbench_->convertValue2Radian(dynamixel_.id.at(0), get_value);
973 }
virtual bool sendJointActuatorValue(std::vector< uint8_t > actuator_id, std::vector< robotis_manipulator::ActuatorValue > value_vector)
Definition: dynamixel.cpp:444
bool writeGoalPosition(std::vector< uint8_t > actuator_id, std::vector< double > radian_vector)
Definition: dynamixel.cpp:266
#define SYNC_WRITE_HANDLER
Definition: dynamixel.h:33
virtual std::vector< robotis_manipulator::ActuatorValue > receiveJointActuatorValue(std::vector< uint8_t > actuator_id)
Definition: dynamixel.cpp:455
bool writeGoalProfilingControlValue(std::vector< uint8_t > actuator_id, std::vector< robotis_manipulator::ActuatorValue > value_vector)
Definition: dynamixel.cpp:604
#define LENGTH_PRESENT_CURRENT_2
Definition: dynamixel.h:49
bool initialize(std::vector< uint8_t > actuator_id, STRING dxl_device_name, STRING dxl_baud_rate)
Definition: dynamixel.cpp:125
bool init(const char *device_name="/dev/ttyUSB0", uint32_t baud_rate=57600, const char **log=NULL)
virtual std::vector< uint8_t > getId()
Definition: dynamixel.cpp:63
bool setOperatingMode(STRING dynamixel_mode="position_mode")
Definition: dynamixel.cpp:852
bool setOperatingMode(std::vector< uint8_t > actuator_id, STRING dynamixel_mode="position_mode")
Definition: dynamixel.cpp:518
#define ADDR_PRESENT_CURRENT_2
Definition: dynamixel.h:39
virtual uint8_t getId()
Definition: dynamixel.cpp:751
virtual void disable()
Definition: dynamixel.cpp:84
virtual robotis_manipulator::ActuatorValue receiveToolActuatorValue()
Definition: dynamixel.cpp:787
virtual bool sendJointActuatorValue(std::vector< uint8_t > actuator_id, std::vector< robotis_manipulator::ActuatorValue > value_vector)
Definition: dynamixel.cpp:100
virtual void init(uint8_t actuator_id, const void *arg)
Definition: dynamixel.cpp:716
bool setSDKHandler(uint8_t actuator_id)
Definition: dynamixel.cpp:564
bool writeProfileValue(STRING profile_mode, uint32_t value)
Definition: dynamixel.cpp:889
virtual void setMode(const void *arg)
Definition: dynamixel.cpp:726
virtual void setMode(std::vector< uint8_t > actuator_id, const void *arg)
Definition: dynamixel.cpp:37
virtual void init(std::vector< uint8_t > actuator_id, const void *arg)
Definition: dynamixel.cpp:27
#define SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT
Definition: dynamixel.h:34
bool writeProfileValue(std::vector< uint8_t > actuator_id, STRING profile_mode, uint32_t value)
Definition: dynamixel.cpp:247
bool setSDKHandler(uint8_t actuator_id)
Definition: dynamixel.cpp:225
virtual std::vector< uint8_t > getId()
Definition: dynamixel.cpp:407
virtual void init(std::vector< uint8_t > actuator_id, const void *arg)
Definition: dynamixel.cpp:371
#define LENGTH_PRESENT_VELOCITY_2
Definition: dynamixel.h:50
bool setOperatingMode(std::vector< uint8_t > actuator_id, STRING dynamixel_mode="position_mode")
Definition: dynamixel.cpp:179
std::vector< robotis_manipulator::ActuatorValue > receiveAllDynamixelValue(std::vector< uint8_t > actuator_id)
Definition: dynamixel.cpp:639
std::vector< robotis_manipulator::ActuatorValue > receiveAllDynamixelValue(std::vector< uint8_t > actuator_id)
Definition: dynamixel.cpp:289
bool writeGoalPosition(double radian)
Definition: dynamixel.cpp:927
bool initialize(uint8_t actuator_id, STRING dxl_device_name, STRING dxl_baud_rate)
Definition: dynamixel.cpp:801
bool initialize(std::vector< uint8_t > actuator_id, STRING dxl_device_name, STRING dxl_baud_rate)
Definition: dynamixel.cpp:464
virtual std::vector< robotis_manipulator::ActuatorValue > receiveJointActuatorValue(std::vector< uint8_t > actuator_id)
Definition: dynamixel.cpp:116
#define ADDR_PRESENT_POSITION_2
Definition: dynamixel.h:41
JointDynamixelProfileControl(float control_loop_time=0.010)
Definition: dynamixel.cpp:366
virtual bool sendToolActuatorValue(robotis_manipulator::ActuatorValue value)
Definition: dynamixel.cpp:782
#define ADDR_PRESENT_VELOCITY_2
Definition: dynamixel.h:40
#define LENGTH_PRESENT_POSITION_2
Definition: dynamixel.h:51
virtual void setMode(std::vector< uint8_t > actuator_id, const void *arg)
Definition: dynamixel.cpp:381
virtual void enable()
Definition: dynamixel.cpp:68
bool writeProfileValue(std::vector< uint8_t > actuator_id, STRING profile_mode, uint32_t value)
Definition: dynamixel.cpp:586
std::string STRING


open_manipulator_libs
Author(s): Darby Lim , Hye-Jong KIM , Ryan Shim , Yong-Ho Na
autogenerated on Mon Jun 10 2019 14:12:00