urdf_model_marker.cpp
Go to the documentation of this file.
1 #include "urdf_parser/urdf_parser.h"
2 #include <iostream>
7 #include <dynamic_tf_publisher/SetDynamicTF.h>
8 #include <Eigen/Geometry>
9 
10 #include <kdl/frames_io.hpp>
11 #include <tf_conversions/tf_kdl.h>
13 #include <boost/filesystem.hpp>
14 
15 using namespace urdf;
16 using namespace std;
17 using namespace im_utils;
18 
19 void UrdfModelMarker::addMoveMarkerControl(visualization_msgs::InteractiveMarker &int_marker, LinkConstSharedPtr link, bool root) {
20  visualization_msgs::InteractiveMarkerControl control;
21  if (root) {
22  im_helpers::add6DofControl(int_marker,false);
23  for(int i=0; i<int_marker.controls.size(); i++) {
24  int_marker.controls[i].always_visible = true;
25  }
26  }
27  else {
28  JointSharedPtr parent_joint = link->parent_joint;
29  Eigen::Vector3f origin_x(1,0,0);
30  Eigen::Vector3f dest_x(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z);
31  Eigen::Quaternionf qua;
32 
33  qua.setFromTwoVectors(origin_x, dest_x);
34  control.orientation.x = qua.x();
35  control.orientation.y = qua.y();
36  control.orientation.z = qua.z();
37  control.orientation.w = qua.w();
38 
39  int_marker.scale = 0.5;
40 
41  switch(parent_joint->type) {
42  case Joint::REVOLUTE:
43  case Joint::CONTINUOUS:
44  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
45  int_marker.controls.push_back(control);
46  break;
47  case Joint::PRISMATIC:
48  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
49  int_marker.controls.push_back(control);
50  break;
51  default:
52  break;
53  }
54  }
55 }
56 
57 void UrdfModelMarker::addInvisibleMeshMarkerControl(visualization_msgs::InteractiveMarker &int_marker, LinkConstSharedPtr link, const std_msgs::ColorRGBA &color) {
58  visualization_msgs::InteractiveMarkerControl control;
59  // ps.pose = UrdfPose2Pose(link->visual->origin);
60  visualization_msgs::Marker marker;
61 
62  //if (use_color) marker.color = color;
63  marker.type = visualization_msgs::Marker::CYLINDER;
64  double scale=0.01;
65  marker.scale.x = scale;
66  marker.scale.y = scale * 1;
67  marker.scale.z = scale * 40;
68  marker.color = color;
69  //marker.pose = stamped.pose;
70  //visualization_msgs::InteractiveMarkerControl control;
71  JointSharedPtr parent_joint = link->parent_joint;
72  Eigen::Vector3f origin_x(0,0,1);
73  Eigen::Vector3f dest_x(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z);
74  Eigen::Quaternionf qua;
75 
76  qua.setFromTwoVectors(origin_x, dest_x);
77  marker.pose.orientation.x = qua.x();
78  marker.pose.orientation.y = qua.y();
79  marker.pose.orientation.z = qua.z();
80  marker.pose.orientation.w = qua.w();
81 
82  control.markers.push_back(marker);
83  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
84  control.always_visible = true;
85 
86  int_marker.controls.push_back(control);
87  return;
88 }
89 
90 
91 void UrdfModelMarker::addGraspPointControl(visualization_msgs::InteractiveMarker &int_marker, std::string link_frame_name_) {
92  //yellow sphere
93  visualization_msgs::InteractiveMarkerControl control;
94  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
95  visualization_msgs::Marker marker;
96  marker.type = visualization_msgs::Marker::SPHERE;
97  marker.scale.x = 0.05;
98  marker.scale.y = 0.05;
99  marker.scale.z = 0.05;
100 
101  marker.color.a = 1.0;
102  marker.color.r = 1.0;
103  marker.color.g = 1.0;
104  marker.color.b = 0.0;
105 
106  control.markers.push_back(marker);
107  control.always_visible = true;
108  int_marker.controls.push_back(control);
109 
110  if (linkMarkerMap[link_frame_name_].gp.displayMoveMarker) {
111  im_helpers::add6DofControl(int_marker,false);
112  }
113 }
114 
115 
116 void UrdfModelMarker::callSetDynamicTf(string parent_frame_id, string frame_id, geometry_msgs::Transform transform) {
117  jsk_topic_tools::ScopedTimer timer = dynamic_tf_check_time_acc_.scopedTimer();
118  dynamic_tf_publisher::SetDynamicTF SetTf;
119  //SetTf.request.freq = 10;
120  SetTf.request.freq = 20;
121  //SetTf.request.freq = 100;
122  SetTf.request.cur_tf.header.stamp = ros::Time::now();
123  SetTf.request.cur_tf.header.frame_id = parent_frame_id;
124  SetTf.request.cur_tf.child_frame_id = frame_id;
125  SetTf.request.cur_tf.transform = transform;
126  if (use_dynamic_tf_ || parent_frame_id == frame_id_) {
127  //std::cout << parent_frame_id << frame_id << std::endl;
129  }
130 }
131 
133  if (use_dynamic_tf_) {
134  std_srvs::Empty req;
135  dynamic_tf_publisher_publish_tf_client.call(req);
136  }
137 }
138 
139 void UrdfModelMarker::publishBasePose(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
140  publishBasePose(feedback->pose, feedback->header);
141 }
142 
143 void UrdfModelMarker::publishBasePose(geometry_msgs::Pose pose, std_msgs::Header header) {
144  geometry_msgs::PoseStamped ps;
145  ps.pose = pose;
146  ps.header = header;
147  pub_base_pose_.publish(ps);
148 }
149 
150 
151 
152 void UrdfModelMarker::publishMarkerPose(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
153  publishMarkerPose(feedback->pose, feedback->header, feedback->marker_name);
154 }
155 
156 void UrdfModelMarker::publishMarkerPose(geometry_msgs::Pose pose, std_msgs::Header header, std::string marker_name) {
157  jsk_interactive_marker::MarkerPose mp;
158  mp.pose.header = header;
159  mp.pose.pose = pose;
160  mp.marker_name = marker_name;
161  mp.type = jsk_interactive_marker::MarkerPose::GENERAL;
162  pub_.publish(mp);
163 }
164 
165 
166 void UrdfModelMarker::publishMarkerMenu(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int menu) {
167  jsk_interactive_marker::MarkerMenu m;
168  m.marker_name = feedback->marker_name;
169  m.menu=menu;
170  pub_move_.publish(m);
171 }
172 
173 void UrdfModelMarker::publishMoveObject(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
174 
175  //jsk_interactive_marker::MoveObject m;
176  jsk_interactive_marker::MarkerMenu m;
177  /*
178  m.goal.pose.header = feedback->header;
179  m.goal.pose.pose = feedback->pose;
180 
181  m.origin.pose.header = feedback->header;
182  m.origin.pose.pose = linkMarkerMap[feedback->marker_name].origin;
183 
184  m.graspPose = linkMarkerMap[feedback->marker_name].gp.pose;
185  pub_move_.publish(m);*/
186 }
187 
188 void UrdfModelMarker::publishJointState(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
189  publishJointState();
190 }
191 
192 void UrdfModelMarker::republishJointState(sensor_msgs::JointState js) {
193  js.header.stamp = ros::Time::now();
194  pub_joint_state_.publish(js);
195 }
196 
197 void UrdfModelMarker::setRootPoseCB(const geometry_msgs::PoseStampedConstPtr &msg) {
198  setRootPose(*msg);
199 }
200 void UrdfModelMarker::setRootPose (geometry_msgs::PoseStamped ps) {
201  try {
202  init_stamp_ = ps.header.stamp;
203  tfl_.transformPose(frame_id_, ps, ps);
204 
205  geometry_msgs::Pose pose = getRootPose(ps.pose);
206 
207  string root_frame = tf_prefix_ + model->getRoot()->name;
208  linkMarkerMap[frame_id_].pose = pose;
209  callSetDynamicTf(frame_id_, root_frame, Pose2Transform(pose));
210  root_pose_ = pose;
211  addChildLinkNames(model->getRoot(), true, false);
212  publishMarkerPose(pose, ps.header, root_frame);
213 
214  }
215  catch (tf::TransformException ex) {
216  ROS_ERROR("%s",ex.what());
217  }
218 
219 }
220 
221 
222 
223 
224 void UrdfModelMarker::resetJointStatesCB(const sensor_msgs::JointStateConstPtr &msg, bool update_root) {
225  boost::mutex::scoped_lock lock(joint_states_mutex_);
226  if (is_joint_states_locked_) {
227  return;
228  }
229  jsk_topic_tools::ScopedTimer timer = reset_joint_states_check_time_acc_.scopedTimer();
230  setJointState(model->getRoot(), msg);
231  republishJointState(*msg);
232 
233  //update root correctly
234  //this may take long time
235  if (update_root) {
236  callPublishTf();
237  ros::spinOnce();
238  }
239  resetRootForVisualization();
240  server_->applyChanges();
241 }
242 
243 
244 void UrdfModelMarker::proc_feedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, string parent_frame_id, string frame_id) {
245  ROS_INFO("proc_feedback");
246  switch (feedback->event_type) {
247  case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
248  case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
249  linkMarkerMap[frame_id].pose = feedback->pose;
250  //root link
251  if (parent_frame_id == frame_id_) {
252  root_pose_ = feedback->pose;
253  publishBasePose(feedback);
254  }
255  callSetDynamicTf(parent_frame_id, frame_id, Pose2Transform(feedback->pose));
256  publishMarkerPose(feedback);
257  publishJointState(feedback);
258  break;
259  case visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK:
260  cout << "clicked" << " frame:" << frame_id << mode_ << endl;
261  //linkMarkerMap[frame_id].displayMoveMarker ^= true;
262  if (mode_ != "visualization") {
263  linkMarkerMap[linkMarkerMap[frame_id].movable_link].displayMoveMarker ^= true;
264  addChildLinkNames(model->getRoot(), true, false);
265  }
266  else {
267  geometry_msgs::PoseStamped ps = getOriginPoseStamped();
268  pub_selected_.publish(ps);
269  jsk_recognition_msgs::Int32Stamped index_msg;
270  index_msg.data = index_;
271  index_msg.header.stamp = init_stamp_;
272  pub_selected_index_.publish(index_msg);
273  }
274  break;
275 
276  }
277  diagnostic_updater_->update();
278 }
279 
280 
281 
282 void UrdfModelMarker::graspPointCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
283  //linkMarkerMap[feedback->marker_name].gp.pose = feedback->pose;
284  //publishMarkerPose(feedback);
285  //publishMarkerMenu(feedback, jsk_interactive_marker::MarkerMenu::MOVE);
286 
287  KDL::Vector graspVec(feedback->mouse_point.x, feedback->mouse_point.y, feedback->mouse_point.z);
288  KDL::Frame parentFrame;
289  tf::poseMsgToKDL (linkMarkerMap[feedback->marker_name].pose, parentFrame);
290 
291  graspVec = parentFrame.Inverse(graspVec);
292 
293  geometry_msgs::Pose p;
294  p.position.x = graspVec.x();
295  p.position.y = graspVec.y();
296  p.position.z = graspVec.z();
297  p.orientation = linkMarkerMap[feedback->marker_name].gp.pose.orientation;
298  linkMarkerMap[feedback->marker_name].gp.pose = p;
299 
300  linkMarkerMap[feedback->marker_name].gp.displayGraspPoint = true;
301  addChildLinkNames(model->getRoot(), true, false);
302  //addChildLinkNames(model->getRoot(), true, false, true, 0);
303 }
304 
305 
306 void UrdfModelMarker::jointMoveCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
307  publishJointState(feedback);
308  sleep(0.5);
309  publishMarkerMenu(feedback, jsk_interactive_marker::MarkerMenu::JOINT_MOVE);
310 }
311 
312 void UrdfModelMarker::resetMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
313 
314  publishJointState(feedback);
315  publishMarkerMenu(feedback, jsk_interactive_marker::MarkerMenu::RESET_JOINT);
316 }
317 
318 void UrdfModelMarker::resetBaseMsgCB(const std_msgs::EmptyConstPtr &msg) {
319  resetBaseCB();
320 }
321 
322 void UrdfModelMarker::resetBaseMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
323  resetBaseCB();
324 }
326  resetRobotBase();
327 
328  geometry_msgs::PoseStamped ps;
329  ps.header.frame_id = frame_id_;
330  ps.pose = root_pose_;
331  setRootPose(ps);
332 
333  // to update root link marker
334  addChildLinkNames(model->getRoot(), true, false);
335 }
336 
338  //set root_pose_ to robot base pose
339  try {
340  tf::StampedTransform transform;
341  geometry_msgs::TransformStamped ts_msg;
342  tfl_.lookupTransform(frame_id_, model->getRoot()->name,
343  ros::Time(0), transform);
344  tf::transformStampedTFToMsg(transform, ts_msg);
345 
346  root_pose_ = Transform2Pose(ts_msg.transform);
347  }
348  catch (tf::TransformException ex) {
349  ROS_ERROR("%s",ex.what());
350  }
351 }
352 
354  if (fixed_link_.size() > 0 && (mode_ == "visualization" || mode_ == "robot")) {
355  string marker_name = tf_prefix_ + model->getRoot()->name;
356  tf::StampedTransform st_offset;
357  bool first_offset = true;
358  for(int i=0; i<fixed_link_.size(); i++) {
359  std::string link = fixed_link_[i];
360  if (!link.empty()) {
361  ROS_DEBUG_STREAM("fixed_link:" << tf_prefix_ + model->getRoot()->name << tf_prefix_ + link);
362  const std::string source_frame = tf_prefix_ + link;
363  const std::string target_frame = tf_prefix_ + model->getRoot()->name;
364  try {
365  tf::StampedTransform st_link_offset;
366  ros::Time now = ros::Time(0);
367  tfl_.waitForTransform(target_frame, source_frame, now, ros::Duration(5.0));
368  tfl_.lookupTransform(target_frame, source_frame,
369  now, st_link_offset);
370 
371  if (first_offset) {
372  st_offset.setRotation(st_link_offset.getRotation());
373  st_offset.setOrigin(st_link_offset.getOrigin());
374  first_offset = false;
375  }
376  else {
377  st_offset.setRotation(st_link_offset.getRotation().slerp(st_offset.getRotation(), (i * 1.0)/(i + 1)));
378  st_offset.setOrigin(st_link_offset.getOrigin().lerp(st_offset.getOrigin(), (i* 1.0)/(i+1)));
379  }
380  }
381  catch (tf::TransformException ex) {
382  ROS_ERROR("Failed to lookup transformation from %s to %s: %s",
383  source_frame.c_str(), target_frame.c_str(),
384  ex.what());
385  }
386  }
387  }
388 
389  //multiply fixed_link_offset_
390  tf::StampedTransform st_fixed_link_offset;
391  geometry_msgs::TransformStamped ts_fixed_link_offset;
392  ts_fixed_link_offset.transform.translation.x = fixed_link_offset_.position.x;
393  ts_fixed_link_offset.transform.translation.y = fixed_link_offset_.position.y;
394  ts_fixed_link_offset.transform.translation.z = fixed_link_offset_.position.z;
395  ts_fixed_link_offset.transform.rotation = fixed_link_offset_.orientation;
396 
397  tf::transformStampedMsgToTF(ts_fixed_link_offset, st_fixed_link_offset);
398 
399  tf::Transform transform;
400  transform = st_offset * st_fixed_link_offset;
401 
402  //convert to root_offset_
403  geometry_msgs::Transform tf_msg;
404  tf::transformTFToMsg(transform, tf_msg);
405 
406  root_offset_.position.x = tf_msg.translation.x;
407  root_offset_.position.y = tf_msg.translation.y;
408  root_offset_.position.z = tf_msg.translation.z;
409  root_offset_.orientation = tf_msg.rotation;
410 
411  //reset root_pose_
412  geometry_msgs::PoseStamped ps;
413  ps.header.stamp = ros::Time::now();
414  ps.header.frame_id = frame_id_;
415  ps.pose.orientation.w = 1.0;
416  //setRootPose(ps);
417  root_pose_ = ps.pose;
418 
419  geometry_msgs::Pose pose = getRootPose(ps.pose);
420 
421  string root_frame = tf_prefix_ + model->getRoot()->name;
422  linkMarkerMap[frame_id_].pose = pose;
423  callSetDynamicTf(frame_id_, root_frame, Pose2Transform(pose));
424 
425  addChildLinkNames(model->getRoot(), true, false);
426  }
427 }
428 
429 
430 
431 
432 void UrdfModelMarker::registrationCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
433 
434  publishJointState(feedback);
435 }
436 
437 void UrdfModelMarker::moveCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
438  /* publish jsk_interactive_marker::MoveModel */
439  jsk_interactive_marker::MoveModel mm;
440  mm.header = feedback->header;
441  mm.name = model_name_;
442  mm.description = model_description_;
443  mm.joint_state_origin = joint_state_origin_;
444  mm.joint_state_goal = joint_state_;
445  mm.pose_origin.header.frame_id = frame_id_;
446  mm.pose_origin.pose = root_pose_origin_;
447  mm.pose_goal.header.frame_id = frame_id_;
448  mm.pose_goal.pose = root_pose_;
449  pub_move_model_.publish(mm);
450 
451 
452  /* publish jsk_interactive_marker::MoveObject */
453  jsk_interactive_marker::MoveObject mo;
454  mo.origin.header = feedback->header;
455  mo.origin.pose = linkMarkerMap[feedback->marker_name].origin;
456 
457  mo.goal.header = feedback->header;
458  mo.goal.pose = feedback->pose;
459 
460  mo.graspPose = linkMarkerMap[feedback->marker_name].gp.pose;
461  pub_move_object_.publish(mo);
462 
463 }
464 
466  cout << "setPose" <<endl;
467  joint_state_origin_ = joint_state_;
468  root_pose_origin_ = root_pose_;
469  setOriginalPose(model->getRoot());
470 }
471 
472 void UrdfModelMarker::setPoseCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
473  setPoseCB();
474 }
475 
476 void UrdfModelMarker::hideMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
477  linkMarkerMap[linkMarkerMap[feedback->marker_name].movable_link].displayMoveMarker = false;
478  addChildLinkNames(model->getRoot(), true, false);
479 }
480 
481 void UrdfModelMarker::hideAllMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
482  map<string, linkProperty>::iterator it = linkMarkerMap.begin();
483  while (it != linkMarkerMap.end())
484  {
485  (*it).second.displayMoveMarker = false;
486  ++it;
487  }
488  addChildLinkNames(model->getRoot(), true, false);
489 }
490 
491 void UrdfModelMarker::hideModelMarkerCB(const std_msgs::EmptyConstPtr &msg) {
492  map<string, linkProperty>::iterator it = linkMarkerMap.begin();
493  while (it != linkMarkerMap.end())
494  {
495  (*it).second.displayModelMarker = false;
496  ++it;
497  }
498  addChildLinkNames(model->getRoot(), true, false);
499 }
500 
501 void UrdfModelMarker::showModelMarkerCB(const std_msgs::EmptyConstPtr &msg) {
502  map<string, linkProperty>::iterator it = linkMarkerMap.begin();
503  while (it != linkMarkerMap.end())
504  {
505  (*it).second.displayModelMarker = true;
506  ++it;
507  }
508  addChildLinkNames(model->getRoot(), true, false);
509 
510 }
511 
512 void UrdfModelMarker::setUrdfCB(const std_msgs::StringConstPtr &msg) {
513  //clear
514  server_->clear();
515  linkMarkerMap.clear();
516 
517  model = parseURDF(msg->data);
518  if (!model) {
519  ROS_ERROR("Model Parsing the xml failed");
520  return;
521  }
522  addChildLinkNames(model->getRoot(), true, true);
523 
524  // start JointState
525  publishJointState();
526  return;
527 }
528 
529 
530 void UrdfModelMarker::graspPoint_feedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, string link_name) {
531  switch (feedback->event_type) {
532  case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
533  linkMarkerMap[link_name].gp.pose = feedback->pose;
534  publishMarkerPose(feedback);
535  break;
536  case visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK:
537  cout << "clicked" << " frame:" << feedback->marker_name << endl;
538  linkMarkerMap[link_name].gp.displayMoveMarker ^= true;
539  addChildLinkNames(model->getRoot(), true, false);
540  break;
541  }
542 }
543 
544 visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeMeshMarkerControl(const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color, bool use_color) {
545  visualization_msgs::Marker meshMarker;
546 
547  if (use_color) meshMarker.color = color;
548  meshMarker.mesh_resource = mesh_resource;
549  meshMarker.mesh_use_embedded_materials = !use_color;
550  meshMarker.type = visualization_msgs::Marker::MESH_RESOURCE;
551 
552  meshMarker.scale = scale;
553  meshMarker.pose = stamped.pose;
554  visualization_msgs::InteractiveMarkerControl control;
555  control.markers.push_back(meshMarker);
556  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
557  control.always_visible = true;
558 
559  return control;
560 }
561 
562 visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeMeshMarkerControl(const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale)
563 {
564  std_msgs::ColorRGBA color;
565  color.r = 0;
566  color.g = 0;
567  color.b = 0;
568  color.a = 0;
569  //color.a = 0.3;
570  return makeMeshMarkerControl(mesh_resource, stamped, scale, color, false);
571  //return makeMeshMarkerControl(mesh_resource, stamped, scale, color, true);
572 }
573 
574 visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeMeshMarkerControl(const std::string &mesh_resource,
575  const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color)
576 {
577  return makeMeshMarkerControl(mesh_resource, stamped, scale, color, true);
578 }
579 
580 visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeCylinderMarkerControl(const geometry_msgs::PoseStamped &stamped, double length, double radius, const std_msgs::ColorRGBA &color, bool use_color) {
581  visualization_msgs::Marker cylinderMarker;
582 
583  if (use_color) cylinderMarker.color = color;
584  cylinderMarker.type = visualization_msgs::Marker::CYLINDER;
585  cylinderMarker.scale.x = radius * 2;
586  cylinderMarker.scale.y = radius * 2;
587  cylinderMarker.scale.z = length;
588  cylinderMarker.pose = stamped.pose;
589 
590  visualization_msgs::InteractiveMarkerControl control;
591  control.markers.push_back(cylinderMarker);
592  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
593  control.always_visible = true;
594 
595  return control;
596 }
597 
598 visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeBoxMarkerControl(const geometry_msgs::PoseStamped &stamped, Vector3 dim, const std_msgs::ColorRGBA &color, bool use_color) {
599  visualization_msgs::Marker boxMarker;
600 
601  fprintf(stderr, "urdfModelMarker = %f %f %f\n", dim.x, dim.y, dim.z);
602  if (use_color) boxMarker.color = color;
603  boxMarker.type = visualization_msgs::Marker::CUBE;
604  boxMarker.scale.x = dim.x;
605  boxMarker.scale.y = dim.y;
606  boxMarker.scale.z = dim.z;
607  boxMarker.pose = stamped.pose;
608 
609  visualization_msgs::InteractiveMarkerControl control;
610  control.markers.push_back(boxMarker);
611  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
612  control.always_visible = true;
613 
614  return control;
615 }
616 
617 visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeSphereMarkerControl(const geometry_msgs::PoseStamped &stamped, double rad, const std_msgs::ColorRGBA &color, bool use_color) {
618  visualization_msgs::Marker sphereMarker;
619 
620  if (use_color) sphereMarker.color = color;
621  sphereMarker.type = visualization_msgs::Marker::SPHERE;
622  sphereMarker.scale.x = rad * 2;
623  sphereMarker.scale.y = rad * 2;
624  sphereMarker.scale.z = rad * 2;
625  sphereMarker.pose = stamped.pose;
626 
627  visualization_msgs::InteractiveMarkerControl control;
628  control.markers.push_back(sphereMarker);
629  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
630  control.always_visible = true;
631 
632  return control;
633 }
634 
636  getJointState();
637  pub_joint_state_.publish(joint_state_);
638 }
639 
641  sensor_msgs::JointState new_joint_state;
642  joint_state_ = new_joint_state;
643  joint_state_.header.stamp = ros::Time::now();
644  getJointState(model->getRoot());
645 }
646 
648 {
649  string link_frame_name_ = tf_prefix_ + link->name;
650  JointSharedPtr parent_joint = link->parent_joint;
651  if (parent_joint != NULL) {
652  KDL::Frame initialFrame;
653  KDL::Frame presentFrame;
655  KDL::Vector rotVec;
656  KDL::Vector jointVec;
657  double jointAngle;
658  double jointAngleAllRange;
659  switch(parent_joint->type) {
660  case Joint::REVOLUTE:
661  case Joint::CONTINUOUS:
662  {
663  linkProperty *link_property = &linkMarkerMap[link_frame_name_];
664  tf::poseMsgToKDL (link_property->initial_pose, initialFrame);
665  tf::poseMsgToKDL (link_property->pose, presentFrame);
666  rot = initialFrame.M.Inverse() * presentFrame.M;
667  jointAngle = rot.GetRotAngle(rotVec);
668  jointVec = KDL::Vector(link_property->joint_axis.x,
669  link_property->joint_axis.y,
670  link_property->joint_axis.z);
671  if (KDL::dot(rotVec,jointVec) < 0) {
672  jointAngle = - jointAngle;
673  }
674  if (link_property->joint_angle > M_PI/2 && jointAngle < -M_PI/2) {
675  link_property->rotation_count += 1;
676  }
677  else if (link_property->joint_angle < -M_PI/2 && jointAngle > M_PI/2) {
678  link_property->rotation_count -= 1;
679  }
680  link_property->joint_angle = jointAngle;
681  jointAngleAllRange = jointAngle + link_property->rotation_count * M_PI * 2;
682 
683  if (parent_joint->type == Joint::REVOLUTE && parent_joint->limits != NULL) {
684  bool changeMarkerAngle = false;
685  if (jointAngleAllRange < parent_joint->limits->lower) {
686  jointAngleAllRange = parent_joint->limits->lower + 0.001;
687  changeMarkerAngle = true;
688  }
689  if (jointAngleAllRange > parent_joint->limits->upper) {
690  jointAngleAllRange = parent_joint->limits->upper - 0.001;
691  changeMarkerAngle = true;
692  }
693 
694  if (changeMarkerAngle) {
695  setJointAngle(link, jointAngleAllRange);
696  }
697  }
698 
699  joint_state_.position.push_back(jointAngleAllRange);
700  joint_state_.name.push_back(parent_joint->name);
701  break;
702  }
703  case Joint::PRISMATIC:
704  {
706  linkProperty *link_property = &linkMarkerMap[link_frame_name_];
707  tf::poseMsgToKDL (link_property->initial_pose, initialFrame);
708  tf::poseMsgToKDL (link_property->pose, presentFrame);
709 
710  pos = presentFrame.p - initialFrame.p;
711 
712  jointVec = KDL::Vector(link_property->joint_axis.x,
713  link_property->joint_axis.y,
714  link_property->joint_axis.z);
715  jointVec = jointVec / jointVec.Norm(); // normalize vector
716  jointAngle = KDL::dot(jointVec, pos);
717 
718  link_property->joint_angle = jointAngle;
719  jointAngleAllRange = jointAngle;
720 
721  if (parent_joint->type == Joint::PRISMATIC && parent_joint->limits != NULL) {
722  bool changeMarkerAngle = false;
723  if (jointAngleAllRange < parent_joint->limits->lower) {
724  jointAngleAllRange = parent_joint->limits->lower + 0.003;
725  changeMarkerAngle = true;
726  }
727  if (jointAngleAllRange > parent_joint->limits->upper) {
728  jointAngleAllRange = parent_joint->limits->upper - 0.003;
729  changeMarkerAngle = true;
730  }
731  if (changeMarkerAngle) {
732  setJointAngle(link, jointAngleAllRange);
733  }
734  }
735 
736  joint_state_.position.push_back(jointAngleAllRange);
737  joint_state_.name.push_back(parent_joint->name);
738  break;
739  }
740  case Joint::FIXED:
741  break;
742  default:
743  break;
744  }
745  server_->applyChanges();
746  }
747 
748  for (std::vector<LinkSharedPtr >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) {
749  getJointState(*child);
750  }
751  return;
752 }
753 
754 void UrdfModelMarker::setJointAngle(LinkConstSharedPtr link, double joint_angle) {
755  string link_frame_name_ = tf_prefix_ + link->name;
756  JointSharedPtr parent_joint = link->parent_joint;
757 
758  if (parent_joint == NULL) {
759  return;
760  }
761 
762  KDL::Frame initialFrame;
763  KDL::Frame presentFrame;
765  KDL::Vector rotVec;
766  KDL::Vector jointVec;
767 
768  std_msgs::Header link_header;
769 
770  int rotation_count = 0;
771 
772  switch(parent_joint->type) {
773  case Joint::REVOLUTE:
774  case Joint::CONTINUOUS:
775  {
776  if (joint_angle > M_PI) {
777  rotation_count = (int)((joint_angle + M_PI) / (M_PI * 2));
778  joint_angle -= rotation_count * M_PI * 2;
779  }
780  else if (joint_angle < -M_PI) {
781  rotation_count = (int)((- joint_angle + M_PI) / (M_PI * 2));
782  joint_angle -= rotation_count * M_PI * 2;
783  }
784  linkProperty *link_property = &linkMarkerMap[link_frame_name_];
785  link_property->joint_angle = joint_angle;
786  link_property->rotation_count = rotation_count;
787 
788  tf::poseMsgToKDL (link_property->initial_pose, initialFrame);
789  tf::poseMsgToKDL (link_property->initial_pose, presentFrame);
790  jointVec = KDL::Vector(link_property->joint_axis.x,
791  link_property->joint_axis.y,
792  link_property->joint_axis.z);
793 
794  presentFrame.M = KDL::Rotation::Rot(jointVec, joint_angle) * initialFrame.M;
795  tf::poseKDLToMsg(presentFrame, link_property->pose);
796 
797  break;
798  }
799  case Joint::PRISMATIC:
800  {
801  linkProperty *link_property = &linkMarkerMap[link_frame_name_];
802  link_property->joint_angle = joint_angle;
803  link_property->rotation_count = rotation_count;
804  tf::poseMsgToKDL (link_property->initial_pose, initialFrame);
805  tf::poseMsgToKDL (link_property->initial_pose, presentFrame);
806  jointVec = KDL::Vector(link_property->joint_axis.x,
807  link_property->joint_axis.y,
808  link_property->joint_axis.z);
809  jointVec = jointVec / jointVec.Norm(); // normalize vector
810  presentFrame.p = joint_angle * jointVec + initialFrame.p;
811  tf::poseKDLToMsg(presentFrame, link_property->pose);
812  break;
813  }
814  default:
815  break;
816  }
817 
818  link_header.stamp = ros::Time(0);
819  link_header.frame_id = linkMarkerMap[link_frame_name_].frame_id;
820 
821  server_->setPose(link_frame_name_, linkMarkerMap[link_frame_name_].pose, link_header);
822  //server_->applyChanges();
823  callSetDynamicTf(linkMarkerMap[link_frame_name_].frame_id, link_frame_name_, Pose2Transform(linkMarkerMap[link_frame_name_].pose));
824 }
825 
826 void UrdfModelMarker::setJointState(LinkConstSharedPtr link, const sensor_msgs::JointStateConstPtr &js)
827 {
828  string link_frame_name_ = tf_prefix_ + link->name;
829  JointSharedPtr parent_joint = link->parent_joint;
830  if (parent_joint != NULL) {
831  KDL::Frame initialFrame;
832  KDL::Frame presentFrame;
834  KDL::Vector rotVec;
835  KDL::Vector jointVec;
836  double jointAngle;
837  bool changeAngle = false;
838  std_msgs::Header link_header;
839  switch(parent_joint->type) {
840  case Joint::REVOLUTE:
841  case Joint::CONTINUOUS:
842  for(int i=0; i< js->name.size(); i++) {
843  if (js->name[i] == parent_joint->name) {
844  jointAngle = js->position[i];
845  changeAngle = true;
846  break;
847  }
848  }
849  if (!changeAngle) {
850  break;
851  }
852  setJointAngle(link, jointAngle);
853  break;
854  case Joint::PRISMATIC:
855  for(int i=0; i< js->name.size(); i++) {
856  if (js->name[i] == parent_joint->name) {
857  jointAngle = js->position[i];
858  changeAngle = true;
859  break;
860  }
861  }
862  if (!changeAngle) {
863  break;
864  }
865  setJointAngle(link, jointAngle);
866  break;
867  default:
868  break;
869  }
870  }
871  for (std::vector<LinkSharedPtr >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) {
872  setJointState(*child, js);
873  }
874  return;
875 }
876 
877 geometry_msgs::Pose UrdfModelMarker::getRootPose(geometry_msgs::Pose pose) {
878  KDL::Frame pose_frame, offset_frame;
879  tf::poseMsgToKDL(pose, pose_frame);
880  tf::poseMsgToKDL(root_offset_, offset_frame);
881  pose_frame = pose_frame * offset_frame.Inverse();
882  tf::poseKDLToMsg(pose_frame, pose);
883  return pose;
884 }
885 
886 geometry_msgs::PoseStamped UrdfModelMarker::getOriginPoseStamped() {
887  geometry_msgs::PoseStamped ps;
888  geometry_msgs::Pose pose;
889  pose = root_pose_;
890  KDL::Frame pose_frame, offset_frame;
891  tf::poseMsgToKDL(pose, pose_frame);
892  tf::poseMsgToKDL(root_offset_, offset_frame);
893  pose_frame = pose_frame * offset_frame;
894  tf::poseKDLToMsg(pose_frame, pose);
895  ps.pose = pose;
896  ps.header.frame_id = frame_id_;
897  ps.header.stamp = init_stamp_;
898  return ps;
899 }
900 
901 
903 {
904  string link_frame_name_ = tf_prefix_ + link->name;
905  linkMarkerMap[link_frame_name_].origin = linkMarkerMap[link_frame_name_].pose;
906 
907  for (std::vector<LinkSharedPtr >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) {
908  setOriginalPose(*child);
909  }
910 }
911 
912 void UrdfModelMarker::addChildLinkNames(LinkConstSharedPtr link, bool root, bool init) {
913  //addChildLinkNames(link, root, init, false, 0);
914  addChildLinkNames(link, root, init, use_visible_color_, 0);
915 }
916 
917 void UrdfModelMarker::addChildLinkNames(LinkConstSharedPtr link, bool root, bool init, bool use_color, int color_index)
918 {
919  geometry_msgs::PoseStamped ps;
920 
921  double scale_factor = 1.02;
922  string link_frame_name_ = tf_prefix_ + link->name;
923  string parent_link_frame_name_;
924  ROS_INFO("link_frame_name: %s", link_frame_name_.c_str());
925  if (root) {
926  parent_link_frame_name_ = frame_id_;
927  //ps.pose = root_pose_;
928  ps.pose = getRootPose(root_pose_);
929  }
930  else {
931  parent_link_frame_name_ = link->parent_joint->parent_link_name;
932  parent_link_frame_name_ = tf_prefix_ + parent_link_frame_name_;
933  ps.pose = UrdfPose2Pose(link->parent_joint->parent_to_joint_origin_transform);
934  }
935  ps.header.frame_id = parent_link_frame_name_;
936  ps.header.stamp = ros::Time(0);
937 
938  //initialize linkProperty
939  if (init) {
940  callSetDynamicTf(parent_link_frame_name_, link_frame_name_, Pose2Transform(ps.pose));
941  linkProperty lp;
942  lp.pose = ps.pose;
943  lp.origin = ps.pose;
944  lp.initial_pose = ps.pose;
945  if (link->parent_joint !=NULL) {
946  lp.joint_axis = link->parent_joint->axis;
947  }
948  lp.joint_angle = 0;
949  lp.rotation_count=0;
950  if (link->parent_joint !=NULL && link->parent_joint->type == Joint::FIXED) {
951  lp.movable_link = linkMarkerMap[parent_link_frame_name_].movable_link;
952  }
953  else {
954  lp.movable_link = link_frame_name_;
955  }
956 
957  linkMarkerMap.insert(map<string, linkProperty>::value_type(link_frame_name_, lp));
958  }
959 
960  linkMarkerMap[link_frame_name_].frame_id = parent_link_frame_name_;
961 
962  visualization_msgs::InteractiveMarker int_marker;
963  int_marker.header = ps.header;
964 
965  int_marker.name = link_frame_name_;
966  if (root) {
967  int_marker.description = model_description_;
968  }
969  int_marker.scale = 1.0;
970  int_marker.pose = ps.pose;
971 
972 
973  if (!init && !root) {
974  visualization_msgs::InteractiveMarker old_marker;
975  if (server_->get(link_frame_name_, old_marker)) {
976  int_marker.pose = old_marker.pose;
977  }
978  }
979 
980 
981  //hide marker
982  if (!linkMarkerMap[link_frame_name_].displayModelMarker) {
983  server_->erase(link_frame_name_);
984  server_->erase(tf_prefix_ + link->name + "/grasp"); //grasp marker
985  }
986  else {
987 
988  //move Marker
989  if (linkMarkerMap[link_frame_name_].displayMoveMarker) {
990  addMoveMarkerControl(int_marker, link, root);
991  }
992  //model Mesh Marker
993  std_msgs::ColorRGBA color;
994  if (mode_ == "visualization") {
995  color.r = (double)0xFF / 0xFF;
996  color.g = (double)0xFF / 0xFF;
997  color.b = (double)0x00 / 0xFF;
998  color.a = 0.5;
999  }
1000  else {
1001  switch(color_index %3) {
1002  case 0:
1003  color.r = (double)0xFF / 0xFF;
1004  color.g = (double)0xC3 / 0xFF;
1005  color.b = (double)0x00 / 0xFF;
1006  break;
1007  case 1:
1008  color.r = (double)0x58 / 0xFF;
1009  color.g = (double)0x0E / 0xFF;
1010  color.b = (double)0xAD / 0xFF;
1011  break;
1012  case 2:
1013  color.r = (double)0x0C / 0xFF;
1014  color.g = (double)0x5A / 0xFF;
1015  color.b = (double)0xA6 / 0xFF;
1016  break;
1017  }
1018  color.a = 1.0;
1019  }
1020 
1021  //link_array
1022  std::vector<VisualSharedPtr > visual_array;
1023  if (link->visual_array.size() != 0) {
1024  visual_array = link->visual_array;
1025  }
1026  else if (link->visual.get() != NULL) {
1027  visual_array.push_back(link->visual);
1028  }
1029  for(int i=0; i<visual_array.size(); i++) {
1030  VisualSharedPtr link_visual = visual_array[i];
1031  if (link_visual.get() != NULL && link_visual->geometry.get() != NULL) {
1032  visualization_msgs::InteractiveMarkerControl meshControl;
1033  if (link_visual->geometry->type == Geometry::MESH) {
1034 #if ROS_VERSION_MINIMUM(1,14,0) // melodic
1035  MeshConstSharedPtr mesh = std::static_pointer_cast<const Mesh>(link_visual->geometry);
1036 #else
1037  MeshConstSharedPtr mesh = boost::static_pointer_cast<const Mesh>(link_visual->geometry);
1038 #endif
1039  string model_mesh_ = mesh->filename;
1040  if (linkMarkerMap[link_frame_name_].mesh_file == "") {
1041  model_mesh_ = getRosPathFromModelPath(model_mesh_);
1042  linkMarkerMap[link_frame_name_].mesh_file = model_mesh_;
1043  }
1044  else {
1045  model_mesh_ = linkMarkerMap[link_frame_name_].mesh_file;
1046  }
1047  ps.pose = UrdfPose2Pose(link_visual->origin);
1048  ROS_DEBUG_STREAM("mesh_file:" << model_mesh_);
1049  geometry_msgs::Vector3 mesh_scale;
1050  mesh_scale.x = mesh->scale.x;
1051  mesh_scale.y = mesh->scale.y;
1052  mesh_scale.z = mesh->scale.z;
1053  ROS_INFO("make mesh marker from %s", model_mesh_.c_str());
1054  if (use_color) {
1055  meshControl = makeMeshMarkerControl(model_mesh_, ps, mesh_scale, color);
1056  }
1057  else {
1058  meshControl = makeMeshMarkerControl(model_mesh_, ps, mesh_scale);
1059  }
1060  }
1061  else if (link_visual->geometry->type == Geometry::CYLINDER) {
1062 #if ROS_VERSION_MINIMUM(1,14,0) // melodic
1063  CylinderConstSharedPtr cylinder = std::static_pointer_cast<const Cylinder>(link_visual->geometry);
1064 #else
1065  CylinderConstSharedPtr cylinder = boost::static_pointer_cast<const Cylinder>(link_visual->geometry);
1066 #endif
1067  ps.pose = UrdfPose2Pose(link_visual->origin);
1068  double length = cylinder->length;
1069  double radius = cylinder->radius;
1070  ROS_INFO_STREAM("cylinder " << link->name << ", length = " << length << ", radius " << radius);
1071  if (use_color) {
1072  meshControl = makeCylinderMarkerControl(ps, length, radius, color, true);
1073  }
1074  else {
1075  meshControl = makeCylinderMarkerControl(ps, length, radius, color, true);
1076  }
1077  }
1078  else if (link_visual->geometry->type == Geometry::BOX) {
1079 #if ROS_VERSION_MINIMUM(1,14,0) // melodic
1080  BoxConstSharedPtr box = std::static_pointer_cast<const Box>(link_visual->geometry);
1081 #else
1082  BoxConstSharedPtr box = boost::static_pointer_cast<const Box>(link_visual->geometry);
1083 #endif
1084  ps.pose = UrdfPose2Pose(link_visual->origin);
1085  Vector3 dim = box->dim;
1086  ROS_INFO_STREAM("box " << link->name << ", dim = " << dim.x << ", " << dim.y << ", " << dim.z);
1087  if (use_color) {
1088  meshControl = makeBoxMarkerControl(ps, dim, color, true);
1089  }
1090  else {
1091  meshControl = makeBoxMarkerControl(ps, dim, color, true);
1092  }
1093  }
1094  else if (link_visual->geometry->type == Geometry::SPHERE) {
1095 #if ROS_VERSION_MINIMUM(1,14,0) // melodic
1096  SphereConstSharedPtr sphere = std::static_pointer_cast<const Sphere>(link_visual->geometry);
1097 #else
1098  SphereConstSharedPtr sphere = boost::static_pointer_cast<const Sphere>(link_visual->geometry);
1099 #endif
1100  ps.pose = UrdfPose2Pose(link_visual->origin);
1101  double rad = sphere->radius;
1102  if (use_color) {
1103  meshControl = makeSphereMarkerControl(ps, rad, color, true);
1104  }
1105  else {
1106  meshControl = makeSphereMarkerControl(ps, rad, color, true);
1107  }
1108  }
1109  int_marker.controls.push_back(meshControl);
1110 
1111  server_->insert(int_marker);
1112  server_->setCallback(int_marker.name,
1113  boost::bind(&UrdfModelMarker::proc_feedback, this, _1, parent_link_frame_name_, link_frame_name_));
1114 
1115  model_menu_.apply(*server_, link_frame_name_);
1116 
1117  }
1118  else {
1119  JointSharedPtr parent_joint = link->parent_joint;
1120  if (parent_joint != NULL) {
1121  if (parent_joint->type==Joint::REVOLUTE || parent_joint->type==Joint::REVOLUTE) {
1122  addInvisibleMeshMarkerControl(int_marker, link, color);
1123  server_->insert(int_marker);
1124  server_->setCallback(int_marker.name,
1125  boost::bind(&UrdfModelMarker::proc_feedback, this, _1, parent_link_frame_name_, link_frame_name_));
1126  model_menu_.apply(*server_, link_frame_name_);
1127  }
1128  }
1129  }
1130  }
1131  if (!robot_mode_) {
1132  //add Grasp Point Marker
1133  if (linkMarkerMap[link_frame_name_].gp.displayGraspPoint) {
1134  visualization_msgs::InteractiveMarker grasp_int_marker;
1135  double grasp_scale_factor = 1.02;
1136  string grasp_link_frame_name_ = tf_prefix_ + link->name + "/grasp";
1137  string grasp_parent_link_frame_name_ = tf_prefix_ + link->name;
1138 
1139  geometry_msgs::PoseStamped grasp_ps;
1140  grasp_ps.pose = linkMarkerMap[link_frame_name_].gp.pose;
1141  grasp_ps.header.frame_id = grasp_parent_link_frame_name_;
1142 
1143  grasp_int_marker.header = grasp_ps.header;
1144  grasp_int_marker.name = grasp_link_frame_name_;
1145  grasp_int_marker.scale = grasp_scale_factor;
1146  grasp_int_marker.pose = grasp_ps.pose;
1147 
1148  addGraspPointControl(grasp_int_marker, link_frame_name_);
1149 
1150  server_->insert(grasp_int_marker);
1151  server_->setCallback(grasp_int_marker.name,
1152  boost::bind(&UrdfModelMarker::graspPoint_feedback, this, _1, link_frame_name_));
1153 
1154  }
1155  }
1156  }
1157 
1158  //initialize JointState
1159  if (init) {
1160  if (!root && initial_pose_map_.count(link->parent_joint->name) != 0) {
1161  setJointAngle(link, initial_pose_map_[link->parent_joint->name]);
1162  }
1163  }
1164 
1165  // cout << "Link:" << link->name << endl;
1166 
1167  for (std::vector<LinkSharedPtr >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) {
1168  addChildLinkNames(*child, false, init, use_color, color_index + 1);
1169  }
1170  if (root) {
1171  server_->applyChanges();
1172  }
1173 }
1174 
1175 
1176 
1178 {}
1179 
1180 UrdfModelMarker::UrdfModelMarker (string model_name, string model_description, string model_file, string frame_id, geometry_msgs::PoseStamped root_pose, geometry_msgs::Pose root_offset, double scale_factor, string mode, bool robot_mode, bool registration, vector<string> fixed_link, bool use_robot_description, bool use_visible_color, map<string, double> initial_pose_map, int index, std::shared_ptr<interactive_markers::InteractiveMarkerServer> server) : nh_(), pnh_("~"), tfl_(nh_),use_dynamic_tf_(true), is_joint_states_locked_(false) {
1182  diagnostic_updater_->setHardwareID(ros::this_node::getName());
1183  diagnostic_updater_->add("Modeling Stats", boost::bind(&UrdfModelMarker::updateDiagnostic, this, _1));
1184 
1185  pnh_.param("server_name", server_name, std::string (""));
1186 
1187  if (server_name == "") {
1189  }
1190 
1191  pnh_.getParam("use_dynamic_tf", use_dynamic_tf_);
1192  if (use_dynamic_tf_) {
1193  ros::service::waitForService("set_dynamic_tf", -1);
1194  dynamic_tf_publisher_client = nh_.serviceClient<dynamic_tf_publisher::SetDynamicTF>("set_dynamic_tf", true);
1195  ros::service::waitForService("publish_tf", -1);
1196  dynamic_tf_publisher_publish_tf_client = nh_.serviceClient<std_srvs::Empty>("publish_tf", true);
1197  }
1198  ROS_INFO_STREAM("use_dynamic_tf_ is " << use_dynamic_tf_);
1199 
1200  if (index != -1) {
1201  stringstream ss;
1202  ss << model_name << index;
1203  model_name_ = ss.str();
1204  }
1205  else {
1206  model_name_ = model_name;
1207  }
1208 
1209  model_description_ = model_description;
1210  server_ = server;
1211  model_file_ = model_file;
1212  frame_id_ = frame_id;
1213  root_offset_ = root_offset;
1214  fixed_link_offset_ = root_offset;
1215  root_pose_ = root_pose.pose;
1216  init_stamp_ = root_pose.header.stamp;
1217  scale_factor_ = scale_factor;
1218  robot_mode_ = robot_mode;
1219  registration_ = registration;
1220  mode_ = mode;
1221  fixed_link_ = fixed_link;
1222  use_robot_description_ = use_robot_description;
1223  use_visible_color_ = use_visible_color;
1224  tf_prefix_ = server_name + "/" + model_name_ + "/";
1225  initial_pose_map_ = initial_pose_map;
1226  index_ = index;
1227 
1228  pub_ = pnh_.advertise<jsk_interactive_marker::MarkerPose> ("pose", 1);
1229  pub_move_ = pnh_.advertise<jsk_interactive_marker::MarkerMenu> ("marker_menu", 1);
1230  pub_move_object_ = pnh_.advertise<jsk_interactive_marker::MoveObject> ("move_object", 1);
1231  pub_move_model_ = pnh_.advertise<jsk_interactive_marker::MoveModel> ("move_model", 1);
1232  pub_selected_ = pnh_.advertise<geometry_msgs::PoseStamped> (model_name + "/selected", 1);
1233  pub_selected_index_ = pnh_.advertise<jsk_recognition_msgs::Int32Stamped> (model_name + "/selected_index", 1);
1234  pub_joint_state_ = pnh_.advertise<sensor_msgs::JointState> (model_name_ + "/joint_states", 1);
1235 
1236  sub_set_root_pose_ = pnh_.subscribe<geometry_msgs::PoseStamped> (model_name_ + "/set_pose", 1, boost::bind(&UrdfModelMarker::setRootPoseCB, this, _1));
1237  sub_reset_joints_ = pnh_.subscribe<sensor_msgs::JointState> (model_name_ + "/reset_joint_states", 1, boost::bind(&UrdfModelMarker::resetJointStatesCB, this, _1, false));
1238  sub_reset_joints_and_root_ = pnh_.subscribe<sensor_msgs::JointState> (model_name_ + "/reset_joint_states_and_root", 1, boost::bind(&UrdfModelMarker::resetJointStatesCB, this, _1, true));
1239 
1240  hide_marker_ = pnh_.subscribe<std_msgs::Empty> (model_name_ + "/hide_marker", 1, boost::bind(&UrdfModelMarker::hideModelMarkerCB, this, _1));
1241  show_marker_ = pnh_.subscribe<std_msgs::Empty> (model_name_ + "/show_marker", 1, boost::bind(&UrdfModelMarker::showModelMarkerCB, this, _1));
1242  sub_set_urdf_ = pnh_.subscribe<std_msgs::String>(model_name_ + "/set_urdf", 1, boost::bind(&UrdfModelMarker::setUrdfCB, this, _1));
1243 
1244  show_marker_ = pnh_.subscribe<std_msgs::Empty> (model_name_ + "/reset_root_pose", 1, boost::bind(&UrdfModelMarker::resetBaseMsgCB, this, _1));
1245 
1246  pub_base_pose_ = pnh_.advertise<geometry_msgs::PoseStamped>(model_name_ + "/base_pose", 1);
1247 
1248 
1249 
1250  /*
1251  serv_set_ = pnh_.advertiseService("set_pose",
1252  &InteractiveMarkerInterface::set_cb, this);
1253  serv_markers_set_ = pnh_.advertiseService("set_markers",
1254  &InteractiveMarkerInterface::markers_set_cb, this);
1255  serv_markers_del_ = pnh_.advertiseService("del_markers",
1256  &InteractiveMarkerInterface::markers_del_cb, this);
1257  serv_reset_ = pnh_.advertiseService("reset_pose",
1258  &InteractiveMarkerInterface::reset_cb, this);
1259  */
1260  if (mode_ == "") {
1261  if (registration_) {
1262  mode_ = "registration";
1263  }
1264  else if (robot_mode_) {
1265  mode_ = "robot";
1266  }
1267  else {
1268  mode_ = "model";
1269  }
1270  }
1271  serv_lock_joint_states_ = pnh_.advertiseService("lock_joint_states",
1273  this);
1274  serv_unlock_joint_states_ = pnh_.advertiseService("unlock_joint_states",
1276  this);
1277 
1278  if (mode_ == "registration") {
1279  model_menu_.insert("Registration",
1280  boost::bind(&UrdfModelMarker::registrationCB, this, _1));
1281  }
1282  else if (mode_ == "visualization") {
1283 
1284  }
1285  else if (mode_ == "robot") {
1287  sub_menu_move_ = model_menu_.insert("Move");
1288  model_menu_.insert(sub_menu_move_, "Joint",
1289  boost::bind(&UrdfModelMarker::jointMoveCB, this, _1));
1290  model_menu_.insert(sub_menu_move_, "Base",
1291  boost::bind(&UrdfModelMarker::publishMarkerMenu, this, _1, jsk_interactive_marker::MarkerMenu::MOVE));
1292 
1294  sub_menu_reset_ = model_menu_.insert("Reset Marker Pose");
1295  model_menu_.insert(sub_menu_reset_, "Joint",
1296  boost::bind(&UrdfModelMarker::resetMarkerCB, this, _1));
1297  model_menu_.insert(sub_menu_reset_, "Base",
1298  boost::bind(&UrdfModelMarker::resetBaseMarkerCB, this, _1));
1299 
1300 
1302  sub_menu_pose_ = model_menu_.insert("Special Pose");
1303 
1304  model_menu_.insert(sub_menu_pose_, "Stand Pose",
1305  boost::bind(&UrdfModelMarker::publishMarkerMenu, this, _1, 100));
1306 
1307  model_menu_.insert(sub_menu_pose_, "Manip Pose",
1308  boost::bind(&UrdfModelMarker::publishMarkerMenu, this, _1, 101));
1309 
1310  //model_menu_.insert("Reset Marker Pose",
1311  //boost::bind(&UrdfModelMarker::resetMarkerCB, this, _1));
1312 
1313 
1314  model_menu_.insert("Hide Marker" ,
1315  boost::bind(&UrdfModelMarker::hideMarkerCB, this, _1));
1316  model_menu_.insert("Hide All Marker" ,
1317  boost::bind(&UrdfModelMarker::hideAllMarkerCB, this, _1));
1318 
1319 
1320  }
1321  else if (mode_ == "model") {
1322  model_menu_.insert("Grasp Point",
1323  boost::bind(&UrdfModelMarker::graspPointCB, this, _1));
1324  model_menu_.insert("Move",
1325  boost::bind(&UrdfModelMarker::moveCB, this, _1));
1326  model_menu_.insert("Set as present pose",
1327  boost::bind(&UrdfModelMarker::setPoseCB, this, _1));
1328  model_menu_.insert("Hide Marker" ,
1329  boost::bind(&UrdfModelMarker::hideMarkerCB, this, _1));
1330  model_menu_.insert("Hide All Marker" ,
1331  boost::bind(&UrdfModelMarker::hideAllMarkerCB, this, _1));
1332  }
1333 
1334  // get the entire file
1335  std::string xml_string;
1336 
1337  if (use_robot_description_) {
1338  ROS_INFO("loading robot_description from parameter %s", model_file_.c_str());
1339  nh_.getParam(model_file_, xml_string);
1340 
1341  }
1342  else {
1343  ROS_INFO_STREAM("loading model_file: " << model_file_);
1346  try {
1347  if (!boost::filesystem::exists(model_file_.c_str())) {
1348  ROS_ERROR("%s does not exists", model_file_.c_str());
1349  }
1350  else {
1351  std::fstream xml_file(model_file_.c_str(), std::fstream::in);
1352  while (xml_file.good())
1353  {
1354  std::string line;
1355  std::getline(xml_file, line);
1356  xml_string += (line + "\n");
1357  }
1358  xml_file.close();
1359  ROS_INFO_STREAM("finish loading model_file: " << model_file_);
1360  }
1361  }
1362  catch (...) {
1363  ROS_ERROR("model or mesh not found: %s", model_file_.c_str());
1364  ROS_ERROR("Please check GAZEBO_MODEL_PATH");
1365  }
1366  }
1367  ROS_INFO("xml_string is %lu size", xml_string.length());
1368  model = parseURDF(xml_string);
1369 
1370  if (!model) {
1371  ROS_ERROR("ERROR: Model Parsing the xml failed");
1372  return;
1373  }
1374  else {
1375  ROS_INFO("model name is %s", model->getName().c_str());
1376  }
1377  if (mode_ == "robot") {
1378  resetRobotBase();
1379  }
1380  addChildLinkNames(model->getRoot(), true, true);
1381 
1383  setPoseCB(); //init joint_state_origin
1384 
1386  geometry_msgs::Pose pose;
1387  pose.orientation.w = 1.0;
1388  //callSetDynamicTf(parent_frame_id, frame_id, Pose2Transform(pose));
1389  return;
1390 }
1391 
1392 bool UrdfModelMarker::lockJointStates(std_srvs::EmptyRequest& req,
1393  std_srvs::EmptyRequest& res)
1394 {
1395  boost::mutex::scoped_lock lock(joint_states_mutex_);
1396  is_joint_states_locked_ = true;
1397  return true;
1398 }
1399 
1400 bool UrdfModelMarker::unlockJointStates(std_srvs::EmptyRequest& req,
1401  std_srvs::EmptyRequest& res)
1402 {
1403  boost::mutex::scoped_lock lock(joint_states_mutex_);
1404  is_joint_states_locked_ = false;
1405  return true;
1406 }
1407 
1408 
1411 {
1412  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "UrdfModelMarker running");
1413  stat.add("Time to set dynamic tf (Avg.)",
1415  stat.add("Time to set dynamic tf (Max)",
1417  stat.add("Time to set dynamic tf (Min)",
1419  stat.add("Time to set dynamic tf (Var.)",
1421 
1422  stat.add("Time to set joint states (Avg.)",
1424  stat.add("Time to set joint states (Max)",
1426  stat.add("Time to set joint states (Min)",
1428  stat.add("Time to set joint states (Var.)",
1430 
1431 }
void addInvisibleMeshMarkerControl(visualization_msgs::InteractiveMarker &int_marker, LinkConstSharedPtr link, const std_msgs::ColorRGBA &color)
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
visualization_msgs::InteractiveMarkerControl makeBoxMarkerControl(const geometry_msgs::PoseStamped &stamped, Vector3 dim, const std_msgs::ColorRGBA &color, bool use_color)
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
ros::Publisher pub_move_
void addMoveMarkerControl(visualization_msgs::InteractiveMarker &int_marker, LinkConstSharedPtr link, bool root)
ros::Publisher pub_base_pose_
ros::Subscriber sub_reset_joints_
void graspPointCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
boost::mutex joint_states_mutex_
void hideAllMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
visualization_msgs::InteractiveMarkerControl makeBoxMarkerControl(const geometry_msgs::PoseStamped &stamped, Vector3 dim, const std_msgs::ColorRGBA &color, bool use_color)
geometry_msgs::Pose root_pose_
pos
ros::Publisher pub_
double GetRotAngle(Vector &axis, double eps=epsilon) const
void republishJointState(sensor_msgs::JointState js)
void addGraspPointControl(visualization_msgs::InteractiveMarker &int_marker, std::string link_frame_name_)
std::string tf_prefix_
void summary(unsigned char lvl, const std::string s)
void showModelMarkerCB(const std_msgs::EmptyConstPtr &msg)
Rotation Inverse() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber show_marker_
ros::Publisher pub_move_model_
std::string getFullPathFromModelPath(std::string path)
std::string target_frame
ros::Subscriber sub_set_root_pose_
void addChildLinkNames(LinkConstSharedPtr link, bool root, bool init)
geometry_msgs::Transform Pose2Transform(const geometry_msgs::Pose pose_msg)
bool call(MReq &req, MRes &res)
geometry_msgs::PoseStamped getOriginPoseStamped()
ROSCPP_DECL const std::string & getName()
void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
void resetJointStatesCB(const sensor_msgs::JointStateConstPtr &msg, bool update_root)
ros::Subscriber sub_reset_joints_and_root_
geometry_msgs::Pose initial_pose
void callSetDynamicTf(string parent_frame_id, string frame_id, geometry_msgs::Transform transform)
ros::Publisher pub_move_object_
visualization_msgs::InteractiveMarkerControl makeSphereMarkerControl(const geometry_msgs::PoseStamped &stamped, double rad, const std_msgs::ColorRGBA &color, bool use_color)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void resetBaseMsgCB(const std_msgs::EmptyConstPtr &msg)
ModelInterfaceSharedPtr model
geometry_msgs::Pose Transform2Pose(const geometry_msgs::Transform tf_msg)
void setUrdfCB(const std_msgs::StringConstPtr &msg)
pose
Quaternion slerp(const Quaternion &q, const tfScalar &t) const
void setOriginalPose(LinkConstSharedPtr link)
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
double z() const
std::string model_file_
visualization_msgs::InteractiveMarkerControl makeMeshMarkerControl(const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color, bool use_color)
std::string frame_id_
ros::ServiceClient dynamic_tf_publisher_client
TFSIMD_FORCE_INLINE Vector3 lerp(const Vector3 &v, const tfScalar &t) const
Rotation M
void publishMarkerPose(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
double Norm(double eps=epsilon) const
void jointMoveCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
scale
void graspPoint_feedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, string link_name)
std::string getRosPathFromModelPath(std::string path)
jsk_topic_tools::TimeAccumulator reset_joint_states_check_time_acc_
void setJointAngle(LinkConstSharedPtr link, double joint_angle)
#define M_PI
void resetMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
double y() const
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
TFSIMD_FORCE_INLINE Vector3()
double x() const
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
std::string model_description_
visualization_msgs::InteractiveMarkerControl makeCylinderMarkerControl(const geometry_msgs::PoseStamped &stamped, double length, double radius, const std_msgs::ColorRGBA &color, bool use_color)
void setRootPose(geometry_msgs::PoseStamped ps)
ros::ServiceServer serv_unlock_joint_states_
ros::ServiceClient dynamic_tf_publisher_publish_tf_client
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
map< string, double > initial_pose_map_
rot
def xml_string(rootXml, addHeader=True)
Frame Inverse() const
geometry_msgs::Pose getRootPose(geometry_msgs::Pose pose)
std::string model_name_
#define ROS_DEBUG_STREAM(args)
ros::NodeHandle pnh_
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void proc_feedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, string parent_frame_id, string frame_id)
void publishBasePose(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
ros::Subscriber hide_marker_
void moveCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void publishMarkerMenu(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int menu)
mutex_t * lock
std::string getFilePathFromRosPath(std::string rospath)
jsk_topic_tools::TimeAccumulator dynamic_tf_check_time_acc_
EntryHandle insert(const std::string &title, const FeedbackCallback &feedback_cb)
geometry_msgs::Pose root_offset_
ros::ServiceServer serv_lock_joint_states_
#define ROS_INFO_STREAM(args)
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
Quaternion getRotation() const
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server_
bool unlockJointStates(std_srvs::EmptyRequest &req, std_srvs::EmptyRequest &res)
void registrationCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
bool getParam(const std::string &key, std::string &s) const
p
void add6DofControl(visualization_msgs::InteractiveMarker &msg, bool fixed=false)
#define NULL
interactive_markers::MenuHandler model_menu_
ros::Publisher pub_selected_index_
ros::Subscriber sub_set_urdf_
static Time now()
void publishMoveObject(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
geometry_msgs::Pose fixed_link_offset_
def sleep(t)
visualization_msgs::InteractiveMarkerControl makeMeshMarkerControl(const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color, bool use_color)
ros::Publisher pub_joint_state_
std::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
static void transformStampedTFToMsg(const StampedTransform &bt, geometry_msgs::TransformStamped &msg)
void resetBaseMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
static Rotation Rot(const Vector &rotvec, double angle)
vector< string > fixed_link_
void add(const std::string &key, const T &val)
std::string server_name
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server
void setRootPoseCB(const geometry_msgs::PoseStampedConstPtr &msg)
ros::NodeHandle nh_
visualization_msgs::InteractiveMarkerControl makeSphereMarkerControl(const geometry_msgs::PoseStamped &stamped, double rad, const std_msgs::ColorRGBA &color, bool use_color)
ROSCPP_DECL void spinOnce()
geometry_msgs::Pose UrdfPose2Pose(const urdf::Pose pose)
static void transformStampedMsgToTF(const geometry_msgs::TransformStamped &msg, StampedTransform &bt)
#define ROS_ERROR(...)
GLdouble radius
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
static void transformTFToMsg(const Transform &bt, geometry_msgs::Transform &msg)
bool lockJointStates(std_srvs::EmptyRequest &req, std_srvs::EmptyRequest &res)
void hideMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void setJointState(LinkConstSharedPtr link, const sensor_msgs::JointStateConstPtr &js)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
visualization_msgs::InteractiveMarkerControl makeCylinderMarkerControl(const geometry_msgs::PoseStamped &stamped, double length, double radius, const std_msgs::ColorRGBA &color, bool use_color)
void hideModelMarkerCB(const std_msgs::EmptyConstPtr &msg)
ros::ServiceClient dynamic_tf_publisher_client
ros::Publisher pub_selected_
timer


jsk_interactive_marker
Author(s): furuta
autogenerated on Sat Mar 20 2021 03:03:33