dynamixel_workbench_controllers.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: Taehun Lim (Darby) */
18 
20 
22  :node_handle_(""),
23  priv_node_handle_("~"),
24  is_joint_state_topic_(false),
25  is_cmd_vel_topic_(false),
26  use_moveit_(false),
27  wheel_separation_(0.0f),
28  wheel_radius_(0.0f),
29  is_moving_(false)
30 {
31  is_joint_state_topic_ = priv_node_handle_.param<bool>("use_joint_states_topic", true);
32  is_cmd_vel_topic_ = priv_node_handle_.param<bool>("use_cmd_vel_topic", false);
33  use_moveit_ = priv_node_handle_.param<bool>("use_moveit", false);
34 
35  read_period_ = priv_node_handle_.param<double>("dxl_read_period", 0.010f);
36  write_period_ = priv_node_handle_.param<double>("dxl_write_period", 0.010f);
37  pub_period_ = priv_node_handle_.param<double>("publish_period", 0.010f);
38 
39  if (is_cmd_vel_topic_ == true)
40  {
41  wheel_separation_ = priv_node_handle_.param<double>("mobile_robot_config/seperation_between_wheels", 0.0);
42  wheel_radius_ = priv_node_handle_.param<double>("mobile_robot_config/radius_of_wheel", 0.0);
43  }
44 
47  jnt_tra_msg_ = new trajectory_msgs::JointTrajectory;
48 }
49 
51 
52 bool DynamixelController::initWorkbench(const std::string port_name, const uint32_t baud_rate)
53 {
54  bool result = false;
55  const char* log;
56 
57  result = dxl_wb_->init(port_name.c_str(), baud_rate, &log);
58  if (result == false)
59  {
60  ROS_ERROR("%s", log);
61  }
62 
63  return result;
64 }
65 
66 bool DynamixelController::getDynamixelsInfo(const std::string yaml_file)
67 {
68  YAML::Node dynamixel;
69  dynamixel = YAML::LoadFile(yaml_file.c_str());
70 
71  if (dynamixel == NULL)
72  return false;
73 
74  for (YAML::const_iterator it_file = dynamixel.begin(); it_file != dynamixel.end(); it_file++)
75  {
76  std::string name = it_file->first.as<std::string>();
77  if (name.size() == 0)
78  {
79  continue;
80  }
81 
82  YAML::Node item = dynamixel[name];
83  for (YAML::const_iterator it_item = item.begin(); it_item != item.end(); it_item++)
84  {
85  std::string item_name = it_item->first.as<std::string>();
86  int32_t value = it_item->second.as<int32_t>();
87 
88  if (item_name == "ID")
89  dynamixel_[name] = value;
90 
91  ItemValue item_value = {item_name, value};
92  std::pair<std::string, ItemValue> info(name, item_value);
93 
94  dynamixel_info_.push_back(info);
95  }
96  }
97 
98  return true;
99 }
100 
102 {
103  bool result = false;
104  const char* log;
105 
106  for (auto const& dxl:dynamixel_)
107  {
108  uint16_t model_number = 0;
109  result = dxl_wb_->ping((uint8_t)dxl.second, &model_number, &log);
110  if (result == false)
111  {
112  ROS_ERROR("%s", log);
113  ROS_ERROR("Can't find Dynamixel ID '%d'", dxl.second);
114  return result;
115  }
116  else
117  {
118  ROS_INFO("Name : %s, ID : %d, Model Number : %d", dxl.first.c_str(), dxl.second, model_number);
119  }
120  }
121 
122  return result;
123 }
124 
126 {
127  const char* log;
128 
129  for (auto const& dxl:dynamixel_)
130  {
131  dxl_wb_->torqueOff((uint8_t)dxl.second);
132 
133  for (auto const& info:dynamixel_info_)
134  {
135  if (dxl.first == info.first)
136  {
137  if (info.second.item_name != "ID" && info.second.item_name != "Baud_Rate")
138  {
139  bool result = dxl_wb_->itemWrite((uint8_t)dxl.second, info.second.item_name.c_str(), info.second.value, &log);
140  if (result == false)
141  {
142  ROS_ERROR("%s", log);
143  ROS_ERROR("Failed to write value[%d] on items[%s] to Dynamixel[Name : %s, ID : %d]", info.second.value, info.second.item_name.c_str(), dxl.first.c_str(), dxl.second);
144  return false;
145  }
146  }
147  }
148  }
149 
150  dxl_wb_->torqueOn((uint8_t)dxl.second);
151  }
152 
153  return true;
154 }
155 
157 {
158  bool result = false;
159  const char* log = NULL;
160 
161  auto it = dynamixel_.begin();
162 
163  const ControlItem *goal_position = dxl_wb_->getItemInfo(it->second, "Goal_Position");
164  if (goal_position == NULL) return false;
165 
166  const ControlItem *goal_velocity = dxl_wb_->getItemInfo(it->second, "Goal_Velocity");
167  if (goal_velocity == NULL) goal_velocity = dxl_wb_->getItemInfo(it->second, "Moving_Speed");
168  if (goal_velocity == NULL) return false;
169 
170  const ControlItem *present_position = dxl_wb_->getItemInfo(it->second, "Present_Position");
171  if (present_position == NULL) return false;
172 
173  const ControlItem *present_velocity = dxl_wb_->getItemInfo(it->second, "Present_Velocity");
174  if (present_velocity == NULL) present_velocity = dxl_wb_->getItemInfo(it->second, "Present_Speed");
175  if (present_velocity == NULL) return false;
176 
177  const ControlItem *present_current = dxl_wb_->getItemInfo(it->second, "Present_Current");
178  if (present_current == NULL) present_current = dxl_wb_->getItemInfo(it->second, "Present_Load");
179  if (present_current == NULL) return false;
180 
181  control_items_["Goal_Position"] = goal_position;
182  control_items_["Goal_Velocity"] = goal_velocity;
183 
184  control_items_["Present_Position"] = present_position;
185  control_items_["Present_Velocity"] = present_velocity;
186  control_items_["Present_Current"] = present_current;
187 
188  return true;
189 }
190 
192 {
193  bool result = false;
194  const char* log = NULL;
195 
196  auto it = dynamixel_.begin();
197 
198  result = dxl_wb_->addSyncWriteHandler(control_items_["Goal_Position"]->address, control_items_["Goal_Position"]->data_length, &log);
199  if (result == false)
200  {
201  ROS_ERROR("%s", log);
202  return result;
203  }
204  else
205  {
206  ROS_INFO("%s", log);
207  }
208 
209  result = dxl_wb_->addSyncWriteHandler(control_items_["Goal_Velocity"]->address, control_items_["Goal_Velocity"]->data_length, &log);
210  if (result == false)
211  {
212  ROS_ERROR("%s", log);
213  return result;
214  }
215  else
216  {
217  ROS_INFO("%s", log);
218  }
219 
220  if (dxl_wb_->getProtocolVersion() == 2.0f)
221  {
222  uint16_t start_address = std::min(control_items_["Present_Position"]->address, control_items_["Present_Current"]->address);
223 
224  /*
225  As some models have an empty space between Present_Velocity and Present Current, read_length is modified as below.
226  */
227  // uint16_t read_length = control_items_["Present_Position"]->data_length + control_items_["Present_Velocity"]->data_length + control_items_["Present_Current"]->data_length;
228  uint16_t read_length = control_items_["Present_Position"]->data_length + control_items_["Present_Velocity"]->data_length + control_items_["Present_Current"]->data_length+2;
229 
230  result = dxl_wb_->addSyncReadHandler(start_address,
231  read_length,
232  &log);
233  if (result == false)
234  {
235  ROS_ERROR("%s", log);
236  return result;
237  }
238  }
239 
240  return result;
241 }
242 
243 bool DynamixelController::getPresentPosition(std::vector<std::string> dxl_name)
244 {
245  bool result = false;
246  const char* log = NULL;
247 
248  int32_t get_position[dxl_name.size()];
249 
250  uint8_t id_array[dxl_name.size()];
251  uint8_t id_cnt = 0;
252 
253  for (auto const& name:dxl_name)
254  {
255  id_array[id_cnt++] = dynamixel_[name];
256  }
257 
258  if (dxl_wb_->getProtocolVersion() == 2.0f)
259  {
261  id_array,
262  dxl_name.size(),
263  &log);
264  if (result == false)
265  {
266  ROS_ERROR("%s", log);
267  }
268 
269  WayPoint wp;
270 
272  id_array,
273  id_cnt,
274  control_items_["Present_Position"]->address,
275  control_items_["Present_Position"]->data_length,
276  get_position,
277  &log);
278 
279  if (result == false)
280  {
281  ROS_ERROR("%s", log);
282  }
283  else
284  {
285  for(uint8_t index = 0; index < id_cnt; index++)
286  {
287  wp.position = dxl_wb_->convertValue2Radian(id_array[index], get_position[index]);
288  pre_goal_.push_back(wp);
289  }
290  }
291  }
292  else if (dxl_wb_->getProtocolVersion() == 1.0f)
293  {
294  WayPoint wp;
295  uint32_t read_position;
296  for (auto const& dxl:dynamixel_)
297  {
298  result = dxl_wb_->readRegister((uint8_t)dxl.second,
299  control_items_["Present_Position"]->address,
300  control_items_["Present_Position"]->data_length,
301  &read_position,
302  &log);
303  if (result == false)
304  {
305  ROS_ERROR("%s", log);
306  }
307 
308  wp.position = dxl_wb_->convertValue2Radian((uint8_t)dxl.second, read_position);
309  pre_goal_.push_back(wp);
310  }
311  }
312 
313  return result;
314 }
315 
317 {
318  dynamixel_state_list_pub_ = priv_node_handle_.advertise<dynamixel_workbench_msgs::DynamixelStateList>("dynamixel_state", 100);
319  if (is_joint_state_topic_) joint_states_pub_ = priv_node_handle_.advertise<sensor_msgs::JointState>("joint_states", 100);
320 }
321 
323 {
326 }
327 
329 {
331 }
332 
334 {
335 #ifdef DEBUG
336  static double priv_read_secs =ros::Time::now().toSec();
337 #endif
338  bool result = false;
339  const char* log = NULL;
340 
341  dynamixel_workbench_msgs::DynamixelState dynamixel_state[dynamixel_.size()];
342  dynamixel_state_list_.dynamixel_state.clear();
343 
344  int32_t get_current[dynamixel_.size()];
345  int32_t get_velocity[dynamixel_.size()];
346  int32_t get_position[dynamixel_.size()];
347 
348  uint8_t id_array[dynamixel_.size()];
349  uint8_t id_cnt = 0;
350 
351  for (auto const& dxl:dynamixel_)
352  {
353  dynamixel_state[id_cnt].name = dxl.first;
354  dynamixel_state[id_cnt].id = (uint8_t)dxl.second;
355 
356  id_array[id_cnt++] = (uint8_t)dxl.second;
357  }
358 #ifndef DEBUG
359  if (is_moving_ == false)
360  {
361 #endif
362  if (dxl_wb_->getProtocolVersion() == 2.0f)
363  {
365  id_array,
366  dynamixel_.size(),
367  &log);
368  if (result == false)
369  {
370  ROS_ERROR("%s", log);
371  }
372 
374  id_array,
375  id_cnt,
376  control_items_["Present_Current"]->address,
377  control_items_["Present_Current"]->data_length,
378  get_current,
379  &log);
380  if (result == false)
381  {
382  ROS_ERROR("%s", log);
383  }
384 
386  id_array,
387  id_cnt,
388  control_items_["Present_Velocity"]->address,
389  control_items_["Present_Velocity"]->data_length,
390  get_velocity,
391  &log);
392  if (result == false)
393  {
394  ROS_ERROR("%s", log);
395  }
396 
398  id_array,
399  id_cnt,
400  control_items_["Present_Position"]->address,
401  control_items_["Present_Position"]->data_length,
402  get_position,
403  &log);
404  if (result == false)
405  {
406  ROS_ERROR("%s", log);
407  }
408 
409  for(uint8_t index = 0; index < id_cnt; index++)
410  {
411  dynamixel_state[index].present_current = get_current[index];
412  dynamixel_state[index].present_velocity = get_velocity[index];
413  dynamixel_state[index].present_position = get_position[index];
414 
415  dynamixel_state_list_.dynamixel_state.push_back(dynamixel_state[index]);
416  }
417  }
418  else if(dxl_wb_->getProtocolVersion() == 1.0f)
419  {
420  uint16_t length_of_data = control_items_["Present_Position"]->data_length +
421  control_items_["Present_Velocity"]->data_length +
422  control_items_["Present_Current"]->data_length;
423  uint32_t get_all_data[length_of_data];
424  uint8_t dxl_cnt = 0;
425  for (auto const& dxl:dynamixel_)
426  {
427  result = dxl_wb_->readRegister((uint8_t)dxl.second,
428  control_items_["Present_Position"]->address,
429  length_of_data,
430  get_all_data,
431  &log);
432  if (result == false)
433  {
434  ROS_ERROR("%s", log);
435  }
436 
437  dynamixel_state[dxl_cnt].present_current = DXL_MAKEWORD(get_all_data[4], get_all_data[5]);
438  dynamixel_state[dxl_cnt].present_velocity = DXL_MAKEWORD(get_all_data[2], get_all_data[3]);
439  dynamixel_state[dxl_cnt].present_position = DXL_MAKEWORD(get_all_data[0], get_all_data[1]);
440 
441  dynamixel_state_list_.dynamixel_state.push_back(dynamixel_state[dxl_cnt]);
442  dxl_cnt++;
443  }
444  }
445 #ifndef DEBUG
446  }
447 #endif
448 
449 #ifdef DEBUG
450  ROS_WARN("[readCallback] diff_secs : %f", ros::Time::now().toSec() - priv_read_secs);
451  priv_read_secs = ros::Time::now().toSec();
452 #endif
453 }
454 
456 {
457 #ifdef DEBUG
458  static double priv_pub_secs =ros::Time::now().toSec();
459 #endif
461 
463  {
464  joint_state_msg_.header.stamp = ros::Time::now();
465 
466  joint_state_msg_.name.clear();
467  joint_state_msg_.position.clear();
468  joint_state_msg_.velocity.clear();
469  joint_state_msg_.effort.clear();
470 
471  uint8_t id_cnt = 0;
472  for (auto const& dxl:dynamixel_)
473  {
474  double position = 0.0;
475  double velocity = 0.0;
476  double effort = 0.0;
477 
478  joint_state_msg_.name.push_back(dxl.first);
479 
480  if (dxl_wb_->getProtocolVersion() == 2.0f)
481  {
482  if (strcmp(dxl_wb_->getModelName((uint8_t)dxl.second), "XL-320") == 0) effort = dxl_wb_->convertValue2Load((int16_t)dynamixel_state_list_.dynamixel_state[id_cnt].present_current);
483  else effort = dxl_wb_->convertValue2Current((int16_t)dynamixel_state_list_.dynamixel_state[id_cnt].present_current);
484  }
485  else if (dxl_wb_->getProtocolVersion() == 1.0f) effort = dxl_wb_->convertValue2Load((int16_t)dynamixel_state_list_.dynamixel_state[id_cnt].present_current);
486 
487  velocity = dxl_wb_->convertValue2Velocity((uint8_t)dxl.second, (int32_t)dynamixel_state_list_.dynamixel_state[id_cnt].present_velocity);
488  position = dxl_wb_->convertValue2Radian((uint8_t)dxl.second, (int32_t)dynamixel_state_list_.dynamixel_state[id_cnt].present_position);
489 
490  joint_state_msg_.effort.push_back(effort);
491  joint_state_msg_.velocity.push_back(velocity);
492  joint_state_msg_.position.push_back(position);
493 
494  id_cnt++;
495  }
496 
498  }
499 
500 #ifdef DEBUG
501  ROS_WARN("[publishCallback] diff_secs : %f", ros::Time::now().toSec() - priv_pub_secs);
502  priv_pub_secs = ros::Time::now().toSec();
503 #endif
504 }
505 
506 void DynamixelController::commandVelocityCallback(const geometry_msgs::Twist::ConstPtr &msg)
507 {
508  bool result = false;
509  const char* log = NULL;
510 
511  double wheel_velocity[dynamixel_.size()];
512  int32_t dynamixel_velocity[dynamixel_.size()];
513 
514  const uint8_t LEFT = 0;
515  const uint8_t RIGHT = 1;
516 
517  double robot_lin_vel = msg->linear.x;
518  double robot_ang_vel = msg->angular.z;
519 
520  uint8_t id_array[dynamixel_.size()];
521  uint8_t id_cnt = 0;
522 
523  float rpm = 0.0;
524  for (auto const& dxl:dynamixel_)
525  {
526  const ModelInfo *modelInfo = dxl_wb_->getModelInfo((uint8_t)dxl.second);
527  rpm = modelInfo->rpm;
528  id_array[id_cnt++] = (uint8_t)dxl.second;
529  }
530 
531 // V = r * w = r * (RPM * 0.10472) (Change rad/sec to RPM)
532 // = r * ((RPM * Goal_Velocity) * 0.10472) => Goal_Velocity = V / (r * RPM * 0.10472) = V * VELOCITY_CONSTATNE_VALUE
533 
534  double velocity_constant_value = 1 / (wheel_radius_ * rpm * 0.10472);
535 
536  wheel_velocity[LEFT] = robot_lin_vel - (robot_ang_vel * wheel_separation_ / 2);
537  wheel_velocity[RIGHT] = robot_lin_vel + (robot_ang_vel * wheel_separation_ / 2);
538 
539  if (dxl_wb_->getProtocolVersion() == 2.0f)
540  {
541  if (strcmp(dxl_wb_->getModelName(id_array[0]), "XL-320") == 0)
542  {
543  if (wheel_velocity[LEFT] == 0.0f) dynamixel_velocity[LEFT] = 0;
544  else if (wheel_velocity[LEFT] < 0.0f) dynamixel_velocity[LEFT] = ((-1.0f) * wheel_velocity[LEFT]) * velocity_constant_value + 1023;
545  else if (wheel_velocity[LEFT] > 0.0f) dynamixel_velocity[LEFT] = (wheel_velocity[LEFT] * velocity_constant_value);
546 
547  if (wheel_velocity[RIGHT] == 0.0f) dynamixel_velocity[RIGHT] = 0;
548  else if (wheel_velocity[RIGHT] < 0.0f) dynamixel_velocity[RIGHT] = ((-1.0f) * wheel_velocity[RIGHT] * velocity_constant_value) + 1023;
549  else if (wheel_velocity[RIGHT] > 0.0f) dynamixel_velocity[RIGHT] = (wheel_velocity[RIGHT] * velocity_constant_value);
550  }
551  else
552  {
553  dynamixel_velocity[LEFT] = wheel_velocity[LEFT] * velocity_constant_value;
554  dynamixel_velocity[RIGHT] = wheel_velocity[RIGHT] * velocity_constant_value;
555  }
556  }
557  else if (dxl_wb_->getProtocolVersion() == 1.0f)
558  {
559  if (wheel_velocity[LEFT] == 0.0f) dynamixel_velocity[LEFT] = 0;
560  else if (wheel_velocity[LEFT] < 0.0f) dynamixel_velocity[LEFT] = ((-1.0f) * wheel_velocity[LEFT]) * velocity_constant_value + 1023;
561  else if (wheel_velocity[LEFT] > 0.0f) dynamixel_velocity[LEFT] = (wheel_velocity[LEFT] * velocity_constant_value);
562 
563  if (wheel_velocity[RIGHT] == 0.0f) dynamixel_velocity[RIGHT] = 0;
564  else if (wheel_velocity[RIGHT] < 0.0f) dynamixel_velocity[RIGHT] = ((-1.0f) * wheel_velocity[RIGHT] * velocity_constant_value) + 1023;
565  else if (wheel_velocity[RIGHT] > 0.0f) dynamixel_velocity[RIGHT] = (wheel_velocity[RIGHT] * velocity_constant_value);
566  }
567 
568  result = dxl_wb_->syncWrite(SYNC_WRITE_HANDLER_FOR_GOAL_VELOCITY, id_array, dynamixel_.size(), dynamixel_velocity, 1, &log);
569  if (result == false)
570  {
571  ROS_ERROR("%s", log);
572  }
573 }
574 
576 {
577 #ifdef DEBUG
578  static double priv_pub_secs =ros::Time::now().toSec();
579 #endif
580  bool result = false;
581  const char* log = NULL;
582 
583  uint8_t id_array[dynamixel_.size()];
584  uint8_t id_cnt = 0;
585 
586  int32_t dynamixel_position[dynamixel_.size()];
587 
588  static uint32_t point_cnt = 0;
589  static uint32_t position_cnt = 0;
590 
591  for (auto const& joint:jnt_tra_msg_->joint_names)
592  {
593  id_array[id_cnt] = (uint8_t)dynamixel_[joint];
594  id_cnt++;
595  }
596 
597  if (is_moving_ == true)
598  {
599  for (uint8_t index = 0; index < id_cnt; index++)
600  dynamixel_position[index] = dxl_wb_->convertRadian2Value(id_array[index], jnt_tra_msg_->points[point_cnt].positions.at(index));
601 
602  result = dxl_wb_->syncWrite(SYNC_WRITE_HANDLER_FOR_GOAL_POSITION, id_array, id_cnt, dynamixel_position, 1, &log);
603  if (result == false)
604  {
605  ROS_ERROR("%s", log);
606  }
607 
608  position_cnt++;
609  if (position_cnt >= jnt_tra_msg_->points[point_cnt].positions.size())
610  {
611  point_cnt++;
612  position_cnt = 0;
613  if (point_cnt >= jnt_tra_msg_->points.size())
614  {
615  is_moving_ = false;
616  point_cnt = 0;
617  position_cnt = 0;
618 
619  ROS_INFO("Complete Execution");
620  }
621  }
622  }
623 
624 #ifdef DEBUG
625  ROS_WARN("[writeCallback] diff_secs : %f", ros::Time::now().toSec() - priv_pub_secs);
626  priv_pub_secs = ros::Time::now().toSec();
627 #endif
628 }
629 
630 void DynamixelController::trajectoryMsgCallback(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
631 {
632  uint8_t id_cnt = 0;
633  bool result = false;
634  WayPoint wp;
635 
636  if (is_moving_ == false)
637  {
638  jnt_tra_msg_->joint_names.clear();
639  jnt_tra_msg_->points.clear();
640  pre_goal_.clear();
641 
642  result = getPresentPosition(msg->joint_names);
643  if (result == false)
644  ROS_ERROR("Failed to get Present Position");
645 
646  for (auto const& joint:msg->joint_names)
647  {
648  ROS_INFO("'%s' is ready to move", joint.c_str());
649 
650  jnt_tra_msg_->joint_names.push_back(joint);
651  id_cnt++;
652  }
653 
654  if (id_cnt != 0)
655  {
656  uint8_t cnt = 0;
657  while(cnt < msg->points.size())
658  {
659  std::vector<WayPoint> goal;
660  for (std::vector<int>::size_type id_num = 0; id_num < msg->points[cnt].positions.size(); id_num++)
661  {
662  wp.position = msg->points[cnt].positions.at(id_num);
663 
664  if (msg->points[cnt].velocities.size() != 0) wp.velocity = msg->points[cnt].velocities.at(id_num);
665  else wp.velocity = 0.0f;
666 
667  if (msg->points[cnt].accelerations.size() != 0) wp.acceleration = msg->points[cnt].accelerations.at(id_num);
668  else wp.acceleration = 0.0f;
669 
670  goal.push_back(wp);
671  }
672 
673  if (use_moveit_ == true)
674  {
675  trajectory_msgs::JointTrajectoryPoint jnt_tra_point_msg;
676 
677  for (uint8_t id_num = 0; id_num < id_cnt; id_num++)
678  {
679  jnt_tra_point_msg.positions.push_back(goal[id_num].position);
680  jnt_tra_point_msg.velocities.push_back(goal[id_num].velocity);
681  jnt_tra_point_msg.accelerations.push_back(goal[id_num].acceleration);
682  }
683 
684  jnt_tra_msg_->points.push_back(jnt_tra_point_msg);
685 
686  cnt++;
687  }
688  else
689  {
690  jnt_tra_->setJointNum((uint8_t)msg->points[cnt].positions.size());
691 
692  double move_time = 0.0f;
693  if (cnt == 0) move_time = msg->points[cnt].time_from_start.toSec();
694  else move_time = msg->points[cnt].time_from_start.toSec() - msg->points[cnt-1].time_from_start.toSec();
695 
696  jnt_tra_->init(move_time,
698  pre_goal_,
699  goal);
700 
701  std::vector<WayPoint> way_point;
702  trajectory_msgs::JointTrajectoryPoint jnt_tra_point_msg;
703 
704  for (double index = 0.0; index < move_time; index = index + write_period_)
705  {
706  way_point = jnt_tra_->getJointWayPoint(index);
707 
708  for (uint8_t id_num = 0; id_num < id_cnt; id_num++)
709  {
710  jnt_tra_point_msg.positions.push_back(way_point[id_num].position);
711  jnt_tra_point_msg.velocities.push_back(way_point[id_num].velocity);
712  jnt_tra_point_msg.accelerations.push_back(way_point[id_num].acceleration);
713  }
714 
715  jnt_tra_msg_->points.push_back(jnt_tra_point_msg);
716  jnt_tra_point_msg.positions.clear();
717  jnt_tra_point_msg.velocities.clear();
718  jnt_tra_point_msg.accelerations.clear();
719  }
720 
721  pre_goal_ = goal;
722  cnt++;
723  }
724  }
725  ROS_INFO("Succeeded to get joint trajectory!");
726  is_moving_ = true;
727  }
728  else
729  {
730  ROS_WARN("Please check joint_name");
731  }
732  }
733  else
734  {
735  ROS_INFO_THROTTLE(1, "Dynamixel is moving");
736  }
737 }
738 
739 bool DynamixelController::dynamixelCommandMsgCallback(dynamixel_workbench_msgs::DynamixelCommand::Request &req,
740  dynamixel_workbench_msgs::DynamixelCommand::Response &res)
741 {
742  bool result = false;
743  const char* log;
744 
745  uint8_t id = req.id;
746  std::string item_name = req.addr_name;
747  int32_t value = req.value;
748 
749  result = dxl_wb_->itemWrite(id, item_name.c_str(), value, &log);
750  if (result == false)
751  {
752  ROS_ERROR("%s", log);
753  ROS_ERROR("Failed to write value[%d] on items[%s] to Dynamixel[ID : %d]", value, item_name.c_str(), id);
754  }
755 
756  res.comm_result = result;
757 
758  return true;
759 }
760 
761 int main(int argc, char **argv)
762 {
763  ros::init(argc, argv, "dynamixel_workbench_controllers");
764  ros::NodeHandle node_handle("");
765 
766  std::string port_name = "/dev/ttyUSB0";
767  uint32_t baud_rate = 57600;
768 
769  if (argc < 2)
770  {
771  ROS_ERROR("Please set '-port_name' and '-baud_rate' arguments for connected Dynamixels");
772  return 0;
773  }
774  else
775  {
776  port_name = argv[1];
777  baud_rate = atoi(argv[2]);
778  }
779 
780  DynamixelController dynamixel_controller;
781 
782  bool result = false;
783 
784  std::string yaml_file = node_handle.param<std::string>("dynamixel_info", "");
785 
786  result = dynamixel_controller.initWorkbench(port_name, baud_rate);
787  if (result == false)
788  {
789  ROS_ERROR("Please check USB port name");
790  return 0;
791  }
792 
793  result = dynamixel_controller.getDynamixelsInfo(yaml_file);
794  if (result == false)
795  {
796  ROS_ERROR("Please check YAML file");
797  return 0;
798  }
799 
800  result = dynamixel_controller.loadDynamixels();
801  if (result == false)
802  {
803  ROS_ERROR("Please check Dynamixel ID or BaudRate");
804  return 0;
805  }
806 
807  result = dynamixel_controller.initDynamixels();
808  if (result == false)
809  {
810  ROS_ERROR("Please check control table (http://emanual.robotis.com/#control-table)");
811  return 0;
812  }
813 
814  result = dynamixel_controller.initControlItems();
815  if (result == false)
816  {
817  ROS_ERROR("Please check control items");
818  return 0;
819  }
820 
821  result = dynamixel_controller.initSDKHandlers();
822  if (result == false)
823  {
824  ROS_ERROR("Failed to set Dynamixel SDK Handler");
825  return 0;
826  }
827 
828  dynamixel_controller.initPublisher();
829  dynamixel_controller.initSubscriber();
830  dynamixel_controller.initServer();
831 
832  ros::Timer read_timer = node_handle.createTimer(ros::Duration(dynamixel_controller.getReadPeriod()), &DynamixelController::readCallback, &dynamixel_controller);
833  ros::Timer write_timer = node_handle.createTimer(ros::Duration(dynamixel_controller.getWritePeriod()), &DynamixelController::writeCallback, &dynamixel_controller);
834  ros::Timer publish_timer = node_handle.createTimer(ros::Duration(dynamixel_controller.getPublishPeriod()), &DynamixelController::publishCallback, &dynamixel_controller);
835 
836  ros::spin();
837 
838  return 0;
839 }
#define SYNC_WRITE_HANDLER_FOR_GOAL_POSITION
bool torqueOff(uint8_t id, const char **log=NULL)
void writeCallback(const ros::TimerEvent &)
void publish(const boost::shared_ptr< M > &message) const
void commandVelocityCallback(const geometry_msgs::Twist::ConstPtr &msg)
void setJointNum(uint8_t joint_num)
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool init(const char *device_name="/dev/ttyUSB0", uint32_t baud_rate=57600, const char **log=NULL)
bool getDynamixelsInfo(const std::string yaml_file)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int32_t convertRadian2Value(uint8_t id, float radian)
bool itemWrite(uint8_t id, const char *item_name, int32_t data, const char **log=NULL)
bool torqueOn(uint8_t id, const char **log=NULL)
bool syncWrite(uint8_t index, int32_t *data, const char **log=NULL)
bool readRegister(uint8_t id, uint16_t address, uint16_t length, uint32_t *data, const char **log=NULL)
std::vector< std::pair< std::string, ItemValue > > dynamixel_info_
const char * getModelName(uint8_t id, const char **log=NULL)
trajectory_msgs::JointTrajectory * jnt_tra_msg_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
float convertValue2Current(uint8_t id, int16_t value)
#define ROS_WARN(...)
float convertValue2Load(int16_t value)
double acceleration
std::vector< WayPoint > getJointWayPoint(double tick)
def DXL_MAKEWORD(a, b)
bool dynamixelCommandMsgCallback(dynamixel_workbench_msgs::DynamixelCommand::Request &req, dynamixel_workbench_msgs::DynamixelCommand::Response &res)
bool addSyncWriteHandler(uint16_t address, uint16_t length, const char **log=NULL)
bool addSyncReadHandler(uint16_t address, uint16_t length, const char **log=NULL)
std::map< std::string, const ControlItem * > control_items_
const ControlItem * getItemInfo(uint8_t id, const char *item_name, const char **log=NULL)
bool ping(uint8_t id, uint16_t *get_model_number, const char **log=NULL)
bool initWorkbench(const std::string port_name, const uint32_t baud_rate)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
float convertValue2Radian(uint8_t id, int32_t value)
void init(double move_time, double control_time, std::vector< WayPoint > start, std::vector< WayPoint > goal)
bool getSyncReadData(uint8_t index, int32_t *data, const char **log=NULL)
sensor_msgs::JointState joint_state_msg_
void readCallback(const ros::TimerEvent &)
bool getPresentPosition(std::vector< std::string > dxl_name)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
#define SYNC_WRITE_HANDLER_FOR_GOAL_VELOCITY
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spin()
const ModelInfo * getModelInfo(uint8_t id, const char **log=NULL)
void publishCallback(const ros::TimerEvent &)
std::map< std::string, uint32_t > dynamixel_
static Time now()
#define ROS_INFO_THROTTLE(rate,...)
int main(int argc, char **argv)
std::vector< WayPoint > pre_goal_
dynamixel_workbench_msgs::DynamixelStateList dynamixel_state_list_
bool syncRead(uint8_t index, const char **log=NULL)
ros::ServiceServer dynamixel_command_server_
void trajectoryMsgCallback(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
float convertValue2Velocity(uint8_t id, int32_t value)
#define ROS_ERROR(...)
float getProtocolVersion(void)
#define SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT


dynamixel_workbench_controllers
Author(s): Darby Lim , Ryan Shim
autogenerated on Mon Sep 28 2020 03:37:06