direct_control_module.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2017 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 /* Author: Kayman */
18 
19 #include <stdio.h>
21 
22 namespace robotis_op
23 {
24 
26  : control_cycle_msec_(0),
27  stop_process_(false),
28  is_moving_(false),
29  is_updated_(false),
30  is_blocked_(false),
31  r_min_diff_(0.07),
32  l_min_diff_(0.07),
33  tra_count_(0),
34  tra_size_(0),
35  default_moving_time_(0.5),
36  default_moving_angle_(30),
37  check_collision_(true),
38  moving_time_(3.0),
39  BASE_INDEX(0),
40  HEAD_INDEX(20),
41  RIGHT_END_EFFECTOR_INDEX(21),
42  RIGHT_ELBOW_INDEX(5),
43  LEFT_END_EFFECTOR_INDEX(22),
44  LEFT_ELBOW_INDEX(6),
45  DEBUG(false)
46 {
47  enable_ = false;
48  module_name_ = "direct_control_module";
50 
52 }
53 
55 {
56  queue_thread_.join();
57 }
58 
59 void DirectControlModule::initialize(const int control_cycle_msec, robotis_framework::Robot *robot)
60 {
62 
63  // init result, joint_id_table
64  int joint_index = 0;
65  for (std::map<std::string, robotis_framework::Dynamixel*>::iterator it = robot->dxls_.begin();
66  it != robot->dxls_.end(); it++)
67  {
68  std::string joint_name = it->first;
69  robotis_framework::Dynamixel* dxl_info = it->second;
70 
71  result_[joint_name] = new robotis_framework::DynamixelState();
72  result_[joint_name]->goal_position_ = dxl_info->dxl_state_->goal_position_;
73 
74  collision_[joint_name] = false;
75 
76  using_joint_name_[joint_name] = joint_index++;
77  }
78 
79  target_position_ = Eigen::MatrixXd::Zero(1, result_.size());
80  present_position_ = Eigen::MatrixXd::Zero(1, result_.size());
81  goal_position_ = Eigen::MatrixXd::Zero(1, result_.size());
82  goal_velocity_ = Eigen::MatrixXd::Zero(1, result_.size());
83  goal_acceleration_ = Eigen::MatrixXd::Zero(1, result_.size());
84 
85  // setting of queue thread
86  queue_thread_ = boost::thread(boost::bind(&DirectControlModule::queueThread, this));
87 
88  control_cycle_msec_ = control_cycle_msec;
89 
90  ros::NodeHandle ros_node;
91 
92  /* get Param */
93  ros_node.param<double>("/robotis/direct_control/default_moving_time", default_moving_time_, default_moving_time_);
94  ros_node.param<double>("/robotis/direct_control/default_moving_angle", default_moving_angle_, default_moving_angle_);
95  ros_node.param<bool>("/robotis/direct_control/check_collision", check_collision_, check_collision_);
96 
97  /* publish topics */
98  status_msg_pub_ = ros_node.advertise<robotis_controller_msgs::StatusMsg>("/robotis/status", 0);
99 }
100 
102 {
103  ros::NodeHandle ros_node;
104  ros::CallbackQueue callback_queue;
105 
106  ros_node.setCallbackQueue(&callback_queue);
107 
108  /* subscribe topics */
109  ros::Subscriber set_head_joint_sub = ros_node.subscribe("/robotis/direct_control/set_joint_states", 1,
111 
112  ros::WallDuration duration(control_cycle_msec_ / 1000.0);
113  while(ros_node.ok())
114  callback_queue.callAvailable(duration);
115 }
116 
117 void DirectControlModule::setJointCallback(const sensor_msgs::JointState::ConstPtr &msg)
118 {
119  if (enable_ == false)
120  {
121  ROS_INFO_THROTTLE(1, "Direct control module is not enable.");
122  publishStatusMsg(robotis_controller_msgs::StatusMsg::STATUS_ERROR, "Not Enable");
123  return;
124  }
125 
126  // wait for updating of present joint states
127  int waiting_count = 0;
128  while(is_updated_ == false)
129  {
130  usleep(control_cycle_msec_ * 1000);
131  if(++waiting_count > 100)
132  {
133  ROS_ERROR("present joint angle is not updated");
134  return;
135  }
136  }
137 
138  // set init joint vel, accel
139  goal_velocity_ = Eigen::MatrixXd::Zero(1, result_.size());
140  goal_acceleration_ = Eigen::MatrixXd::Zero(1, result_.size());
141 
142  if (is_moving_ == true)
143  {
144  goal_velocity_ = calc_joint_vel_tra_.block(tra_count_, 0, 1, result_.size());
145  goal_acceleration_ = calc_joint_accel_tra_.block(tra_count_, 0, 1, result_.size());
146  }
147 
148  // moving time
149  moving_time_ = default_moving_time_; // default : 0.5 sec
150 
151  // set target joint angle
152  target_position_ = goal_position_; // default is goal position
153 
154  for (int ix = 0; ix < msg->name.size(); ix++)
155  {
156  std::string joint_name = msg->name[ix];
157  std::map<std::string, int>::iterator joint_it = using_joint_name_.find(joint_name);
158 
159  if (joint_it != using_joint_name_.end())
160  {
161  double target_position = 0.0;
162  int joint_index = joint_it->second;
163 
164  // set target position
165  target_position = msg->position[ix];
166 
167  // check angle limit
168 
169  // apply target position
170  target_position_.coeffRef(0, joint_index) = target_position;
171 
172  // set time
173  double angle_unit = default_moving_angle_ * M_PI / 180;
174  double calc_moving_time = fabs(goal_position_.coeff(0, joint_index) - target_position_.coeff(0, joint_index))
175  / angle_unit;
176  if (calc_moving_time > moving_time_)
177  moving_time_ = calc_moving_time;
178 
179  if (DEBUG)
180  std::cout << "joint : " << joint_name << ", Index : " << joint_index << ", Angle : " << msg->position[ix]
181  << ", Time : " << moving_time_ << std::endl;
182 
183  // in case of moving and collision
184  if(collision_[joint_name] == true)
185  {
186  goal_velocity_.coeffRef(0, joint_index) = 0.0;
187  goal_acceleration_.coeffRef(0, joint_index) = 0.0;
188  }
189  }
190  }
191 
192  if(check_collision_ == true)
193  {
194  // check collision of target angle
195  will_be_collision_ = false;
196  OP3KinematicsDynamics *op3_kinematics_for_target = new OP3KinematicsDynamics(WholeBody);
197  // set goal angle and run forward kinematics
198  for ( std::map<std::string, int>::iterator joint_index_it = using_joint_name_.begin();
199  joint_index_it != using_joint_name_.end(); joint_index_it++)
200  {
201  std::string joint_name = joint_index_it->first;
202  int index = joint_index_it->second;
203  double target_position = target_position_.coeff(0, index);
204 
205  LinkData *op3_link = op3_kinematics_for_target->getLinkData(joint_name);
206  if(op3_link != NULL)
207  op3_link->joint_angle_ = target_position;
208  }
209 
210  op3_kinematics_for_target->calcForwardKinematics(0);
211 
212  double diff_length = 0.0;
213  bool result = getDiff(op3_kinematics_for_target, RIGHT_END_EFFECTOR_INDEX, BASE_INDEX, diff_length);
214  if(result == true && diff_length < 0.075)
215  will_be_collision_ = true;
216 
217  diff_length = 0.0;
218  result = getDiff(op3_kinematics_for_target, LEFT_END_EFFECTOR_INDEX, BASE_INDEX, diff_length);
219  if(result == true && diff_length < 0.075)
220  will_be_collision_ = true;
221  }
222 
223  // generate trajectory
224  tra_gene_thread_ = new boost::thread(boost::bind(&DirectControlModule::jointTraGeneThread, this));
225  delete tra_gene_thread_;
226 }
227 
228 void DirectControlModule::process(std::map<std::string, robotis_framework::Dynamixel *> dxls,
229  std::map<std::string, double> sensors)
230 {
231  if (enable_ == false)
232  return;
233 
234  tra_lock_.lock();
235 
236  // get joint data from robot
237  for (std::map<std::string, robotis_framework::DynamixelState *>::iterator state_it = result_.begin();
238  state_it != result_.end(); state_it++)
239  {
240  std::string joint_name = state_it->first;
241  int index = using_joint_name_[joint_name];
242 
243  robotis_framework::Dynamixel *_dxl = NULL;
244  std::map<std::string, robotis_framework::Dynamixel*>::iterator dxl_it = dxls.find(joint_name);
245  if (dxl_it != dxls.end())
246  _dxl = dxl_it->second;
247  else
248  continue;
249 
250  present_position_.coeffRef(0, index) = _dxl->dxl_state_->present_position_;
251  goal_position_.coeffRef(0, index) = _dxl->dxl_state_->goal_position_;
252  result_[joint_name]->goal_position_ = _dxl->dxl_state_->goal_position_;
253  collision_[joint_name] = false;
254  }
255 
256  is_updated_ = true;
257 
258  // check to stop
259  if (stop_process_ == true)
260  {
261  stopMoving();
262  }
263  else
264  {
265  // process
266  if (tra_size_ != 0)
267  {
268  // start of steps
269  if (tra_count_ == 0)
270  {
271  startMoving();
272  }
273 
274  // end of steps
275  if (tra_count_ >= tra_size_)
276  {
277  finishMoving();
278  }
279  else
280  {
281  // update goal position
282  goal_position_ = calc_joint_tra_.block(tra_count_, 0, 1, result_.size());
283  tra_count_ += 1;
284  }
285  }
286  }
287  tra_lock_.unlock();
288 
289  if(check_collision_ == true)
290  {
291  // set goal angle and run forward kinematics
292  for (std::map<std::string, robotis_framework::DynamixelState *>::iterator state_it = result_.begin();
293  state_it != result_.end(); state_it++)
294  {
295  std::string joint_name = state_it->first;
296  int index = using_joint_name_[joint_name];
297  double goal_position = goal_position_.coeff(0, index);
298 
299  LinkData *op3_link = op3_kinematics_->getLinkData(joint_name);
300  if(op3_link != NULL)
301  op3_link->joint_angle_ = goal_position;
302  }
303 
305 
306  // check self collision
307  bool collision_result = checkSelfCollision();
308  }
309 
310  // set joint data to robot
311  for (std::map<std::string, robotis_framework::DynamixelState *>::iterator state_it = result_.begin();
312  state_it != result_.end(); state_it++)
313  {
314  std::string joint_name = state_it->first;
315  int index = using_joint_name_[joint_name];
316  double goal_position = goal_position_.coeff(0, index);
317 
318  if(collision_[joint_name] == false || check_collision_ == false)
319  result_[joint_name]->goal_position_ = goal_position;
320  }
321 }
322 
324 {
325  tra_lock_.lock();
326 
327  if (is_moving_ == true)
328  stop_process_ = true;
329 
330  tra_lock_.unlock();
331 
332  return;
333 }
334 
336 {
337  return is_moving_;
338 }
339 
341 {
342  is_updated_ = false;
343  is_blocked_ = false;
344  r_min_diff_ = 0.07;
345  l_min_diff_ = 0.07;
346 }
347 
349 {
350 
351 }
352 
354 {
355  is_moving_ = true;
356 
357  // start procedure
358 }
359 
361 {
362  // init value
364  tra_size_ = 0;
365  tra_count_ = 0;
366  is_moving_ = false;
367 
368  // log
369  publishStatusMsg(robotis_controller_msgs::StatusMsg::STATUS_INFO, "Head movement is finished.");
370 
371  if (DEBUG)
372  std::cout << "Trajectory End" << std::endl;
373 }
374 
376 {
377  // init value
379  tra_size_ = 0;
380  tra_count_ = 0;
381  is_moving_ = false;
382  stop_process_ = false;
383 
384  // log
385  publishStatusMsg(robotis_controller_msgs::StatusMsg::STATUS_WARN, "Stop Module.");
386 }
387 
388 /*
389  simple minimum jerk trajectory
390 
391  pos_start : position at initial state
392  vel_start : velocity at initial state
393  accel_start : acceleration at initial state
394 
395  pos_end : position at final state
396  vel_end : velocity at final state
397  accel_end : acceleration at final state
398 
399  smp_time : sampling time
400 
401  mov_time : movement time
402  */
403 Eigen::MatrixXd DirectControlModule::calcMinimumJerkTraPVA(double pos_start, double vel_start, double accel_start,
404  double pos_end, double vel_end, double accel_end,
405  double smp_time, double mov_time)
406 {
407  Eigen::MatrixXd poly_matrix(3, 3);
408  Eigen::MatrixXd poly_vector(3, 1);
409 
410  poly_matrix << robotis_framework::powDI(mov_time, 3), robotis_framework::powDI(mov_time, 4), robotis_framework::powDI(
411  mov_time, 5), 3 * robotis_framework::powDI(mov_time, 2), 4 * robotis_framework::powDI(mov_time, 3), 5
412  * robotis_framework::powDI(mov_time, 4), 6 * mov_time, 12 * robotis_framework::powDI(mov_time, 2), 20
413  * robotis_framework::powDI(mov_time, 3);
414 
415  poly_vector << pos_end - pos_start - vel_start * mov_time - accel_start * pow(mov_time, 2) / 2, vel_end - vel_start
416  - accel_start * mov_time, accel_end - accel_start;
417 
418  Eigen::MatrixXd poly_coeff = poly_matrix.inverse() * poly_vector;
419 
420  int all_time_steps = round(mov_time / smp_time + 1);
421 
422  Eigen::MatrixXd time = Eigen::MatrixXd::Zero(all_time_steps, 1);
423  Eigen::MatrixXd minimum_jer_tra = Eigen::MatrixXd::Zero(all_time_steps, 3);
424 
425  for (int step = 0; step < all_time_steps; step++)
426  time.coeffRef(step, 0) = step * smp_time;
427 
428  for (int step = 0; step < all_time_steps; step++)
429  {
430  // position
431  minimum_jer_tra.coeffRef(step, 0) = pos_start + vel_start * time.coeff(step, 0)
432  + 0.5 * accel_start * robotis_framework::powDI(time.coeff(step, 0), 2)
433  + poly_coeff.coeff(0, 0) * robotis_framework::powDI(time.coeff(step, 0), 3)
434  + poly_coeff.coeff(1, 0) * robotis_framework::powDI(time.coeff(step, 0), 4)
435  + poly_coeff.coeff(2, 0) * robotis_framework::powDI(time.coeff(step, 0), 5);
436  // velocity
437  minimum_jer_tra.coeffRef(step, 1) = vel_start + accel_start * time.coeff(step, 0)
438  + 3 * poly_coeff.coeff(0, 0) * robotis_framework::powDI(time.coeff(step, 0), 2)
439  + 4 * poly_coeff.coeff(1, 0) * robotis_framework::powDI(time.coeff(step, 0), 3)
440  + 5 * poly_coeff.coeff(2, 0) * robotis_framework::powDI(time.coeff(step, 0), 4);
441  // accel
442  minimum_jer_tra.coeffRef(step, 2) = accel_start + 6 * poly_coeff.coeff(0, 0) * time.coeff(step, 0)
443  + 12 * poly_coeff.coeff(1, 0) * robotis_framework::powDI(time.coeff(step, 0), 2)
444  + 20 * poly_coeff.coeff(2, 0) * robotis_framework::powDI(time.coeff(step, 0), 3);
445  }
446 
447  return minimum_jer_tra;
448 }
449 
450 // checking self-collision of both arms
452 {
453  bool collision_result = false;
454  double collision_boundary = will_be_collision_ ? 0.075 : 0.055;
455 
456  // right arm : end-effector
457  // get length between right arm and base
458  double diff_length = 0.0;
459  bool result = getDiff(op3_kinematics_, RIGHT_END_EFFECTOR_INDEX, BASE_INDEX, diff_length);
460 
461  // check collision
462  if(result == true && diff_length < collision_boundary)
463  {
464  if(DEBUG == true)
465  ROS_WARN_STREAM_THROTTLE(1, "Self Collision : RIGHT_ARM and BASE | " << diff_length << " / " << collision_boundary);
466  collision_["r_sho_pitch"] = true;
467  collision_["r_sho_roll"] = true;
468  collision_["r_el"] = true;
469 
470  collision_result = true;
471  }
472 
473  // right arm : elbow
474  // get length between right elbow and base
475  diff_length = 0.0;
476  result = getDiff(op3_kinematics_, RIGHT_ELBOW_INDEX, BASE_INDEX, diff_length);
477 
478  // check collision
479  if(result == true && diff_length < collision_boundary)
480  {
481  if(DEBUG == true)
482  ROS_WARN_STREAM_THROTTLE(1, "Self Collision : RIGHT_ELBOW and BASE | " << diff_length << " / " << collision_boundary);
483  collision_["r_sho_pitch"] = true;
484  collision_["r_sho_roll"] = true;
485 
486  collision_result = true;
487  }
488 
489  // left arm : end-effector
490  // get left arm end effect position
491  diff_length = 0.0;
493 
494  // check collision
495  if(result == true && diff_length < collision_boundary)
496  {
497  if(DEBUG == true)
498  ROS_WARN_STREAM_THROTTLE(1, "Self Collision : LEFT_ARM and BASE | " << diff_length << " / " << collision_boundary);
499  collision_["l_sho_pitch"] = true;
500  collision_["l_sho_roll"] = true;
501  collision_["l_el"] = true;
502 
503  collision_result = true;
504  }
505 
506  // left arm : elbow
507  // get length between left elbow and base
508  diff_length = 0.0;
509  result = getDiff(op3_kinematics_, LEFT_ELBOW_INDEX, BASE_INDEX, diff_length);
510 
511  // check collision
512  if(result == true && diff_length < collision_boundary)
513  {
514  if(DEBUG == true)
515  ROS_WARN_STREAM_THROTTLE(1, "Self Collision : LEFT_ELBOW and BASE | " << diff_length << " / " << collision_boundary);
516  collision_["l_sho_pitch"] = true;
517  collision_["l_sho_roll"] = true;
518 
519  collision_result = true;
520  }
521 
522  if(collision_result == false && DEBUG == true)
523  ROS_WARN("============================================");
524 
525  return collision_result;
526 }
527 
528 bool DirectControlModule::getDiff(OP3KinematicsDynamics *kinematics, int end_index, int base_index, double &diff)
529 {
530  if(kinematics->op3_link_data_[end_index] == NULL | kinematics->op3_link_data_[base_index] == NULL)
531  return false;
532 
533  Eigen::Vector3d end_position = kinematics->op3_link_data_[end_index]->position_;
534  Eigen::Vector3d base_position = kinematics->op3_link_data_[base_index]->position_;
535  Eigen::Vector3d diff_vec = base_position - end_position;
536  diff_vec.coeffRef(2) = 0;
537 
538  diff = diff_vec.norm();
539 
540  ROS_WARN_STREAM_COND(DEBUG, "\nBase Position [" << base_position.coeff(0) << ", " << base_position.coeff(1) << ", " << base_position.coeff(2) << "] \n"
541  << "End Position [" << end_position.coeff(0) << ", " << end_position.coeff(1) << ", " << end_position.coeff(2) << "] \n"
542  << "Diff : " << diff);
543 
544  return true;
545 }
546 
548 {
549  tra_lock_.lock();
550 
551  double smp_time = control_cycle_msec_ * 0.001; // ms -> s
552  int all_time_steps = int(moving_time_ / smp_time) + 1;
553 
554  // for debug
555  try
556  {
557  calc_joint_tra_.resize(all_time_steps, result_.size());
558  calc_joint_vel_tra_.resize(all_time_steps, result_.size());
559  calc_joint_accel_tra_.resize(all_time_steps, result_.size());
560  }
561  catch(std::exception &e)
562  {
563  std::cout << "All step tile : " << all_time_steps << std::endl;
564  std::cout << e.what() << std::endl;
565  throw;
566  }
567 
568  for (std::map<std::string, robotis_framework::DynamixelState *>::iterator state_it = result_.begin();
569  state_it != result_.end(); state_it++)
570  {
571  std::string joint_name = state_it->first;
572  int index = using_joint_name_[joint_name];
573 
574  double ini_pos = goal_position_.coeff(0, index);
575  double ini_vel = goal_velocity_.coeff(0, index);
576  double ini_accel = goal_acceleration_.coeff(0, index);
577 
578  double tar_value = target_position_.coeff(0, index);
579 
580  Eigen::MatrixXd tra = calcMinimumJerkTraPVA(ini_pos, ini_vel, ini_accel, tar_value, 0.0, 0.0, smp_time,
581  moving_time_);
582 
583  calc_joint_tra_.block(0, index, all_time_steps, 1) = tra.block(0, Position, all_time_steps, 1);
584  calc_joint_vel_tra_.block(0, index, all_time_steps, 1) = tra.block(0, Velocity, all_time_steps, 1);
585  calc_joint_accel_tra_.block(0, index, all_time_steps, 1) = tra.block(0, Acceleration, all_time_steps, 1);
586  }
587 
588  tra_size_ = calc_joint_tra_.rows();
589  tra_count_ = 0;
590 
591  if (DEBUG)
592  ROS_INFO("[ready] make trajectory : %d, %d", tra_size_, tra_count_);
593 
594  tra_lock_.unlock();
595 }
596 
597 void DirectControlModule::publishStatusMsg(unsigned int type, std::string msg)
598 {
599  ros::Time now = ros::Time::now();
600 
601  if(msg.compare(last_msg_) == 0)
602  {
603  ros::Duration dur = now - last_msg_time_;
604  if(dur.sec < 1)
605  return;
606  }
607 
608  robotis_controller_msgs::StatusMsg status_msg;
609  status_msg.header.stamp = now;
610  status_msg.type = type;
611  status_msg.module_name = "Direct Control";
612  status_msg.status_msg = msg;
613 
614  status_msg_pub_.publish(status_msg);
615 
616  last_msg_ = msg;
617  last_msg_time_ = now;
618 }
619 }
void setJointCallback(const sensor_msgs::JointState::ConstPtr &msg)
std::map< std::string, DynamixelState * > result_
bool getDiff(OP3KinematicsDynamics *kinematics, int end_index, int base_index, double &diff)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void process(std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, double > sensors)
LinkData * op3_link_data_[ALL_JOINT_ID+1]
void calcForwardKinematics(int joint_ID)
#define ROS_WARN(...)
std::map< std::string, Dynamixel * > dxls_
OP3KinematicsDynamics * op3_kinematics_
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void setCallbackQueue(CallbackQueueInterface *queue)
void initialize(const int control_cycle_msec, robotis_framework::Robot *robot)
std::map< std::string, int > using_joint_name_
#define ROS_WARN_STREAM_COND(cond, args)
Eigen::MatrixXd calcMinimumJerkTraPVA(double pos_start, double vel_start, double accel_start, double pos_end, double vel_end, double accel_end, double smp_time, double mov_time)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM_THROTTLE(rate, args)
double powDI(double a, int b)
Eigen::MatrixXd position_
DynamixelState * dxl_state_
static Time now()
#define ROS_INFO_THROTTLE(rate,...)
LinkData * getLinkData(const std::string link_name)
void publishStatusMsg(unsigned int type, std::string msg)
bool ok() const
std::map< std::string, bool > collision_
#define ROS_ERROR(...)


op3_direct_control_module
Author(s): Kayman
autogenerated on Mon Jun 10 2019 14:41:17