urdf_model_marker.cpp
Go to the documentation of this file.
00001 #include "urdf_parser/urdf_parser.h"
00002 #include <iostream>
00003 #include <interactive_markers/tools.h>
00004 #include <jsk_interactive_marker/urdf_model_marker.h>
00005 #include <jsk_interactive_marker/interactive_marker_utils.h>
00006 #include <jsk_interactive_marker/interactive_marker_helpers.h>
00007 #include <dynamic_tf_publisher/SetDynamicTF.h>
00008 #include <Eigen/Geometry>
00009 
00010 #include <kdl/frames_io.hpp>
00011 #include <tf_conversions/tf_kdl.h>
00012 #include <jsk_topic_tools/log_utils.h>
00013 #include <boost/filesystem.hpp>
00014 
00015 using namespace urdf;
00016 using namespace std;
00017 using namespace im_utils;
00018 
00019 void UrdfModelMarker::addMoveMarkerControl(visualization_msgs::InteractiveMarker &int_marker, LinkConstSharedPtr link, bool root) {
00020   visualization_msgs::InteractiveMarkerControl control;
00021   if (root) {
00022     im_helpers::add6DofControl(int_marker,false);
00023     for(int i=0; i<int_marker.controls.size(); i++) {
00024       int_marker.controls[i].always_visible = true;
00025     }
00026   }
00027   else {
00028     JointSharedPtr parent_joint = link->parent_joint;
00029     Eigen::Vector3f origin_x(1,0,0);
00030     Eigen::Vector3f dest_x(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z);
00031     Eigen::Quaternionf qua;
00032 
00033     qua.setFromTwoVectors(origin_x, dest_x);
00034     control.orientation.x = qua.x();
00035     control.orientation.y = qua.y();
00036     control.orientation.z = qua.z();
00037     control.orientation.w = qua.w();
00038 
00039     int_marker.scale = 0.5;
00040 
00041     switch(parent_joint->type) {
00042     case Joint::REVOLUTE:
00043     case Joint::CONTINUOUS:
00044       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00045       int_marker.controls.push_back(control);
00046       break;
00047     case Joint::PRISMATIC:
00048       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00049       int_marker.controls.push_back(control);
00050       break;
00051     default:
00052       break;
00053     }
00054   }
00055 }
00056 
00057 void UrdfModelMarker::addInvisibleMeshMarkerControl(visualization_msgs::InteractiveMarker &int_marker, LinkConstSharedPtr link, const std_msgs::ColorRGBA &color) {
00058   visualization_msgs::InteractiveMarkerControl control;
00059   //    ps.pose = UrdfPose2Pose(link->visual->origin);
00060   visualization_msgs::Marker marker;
00061 
00062   //if (use_color) marker.color = color;
00063   marker.type = visualization_msgs::Marker::CYLINDER;
00064   double scale=0.01;
00065   marker.scale.x = scale;
00066   marker.scale.y = scale * 1;
00067   marker.scale.z = scale * 40;
00068   marker.color = color;
00069   //marker.pose = stamped.pose;
00070   //visualization_msgs::InteractiveMarkerControl control;
00071   JointSharedPtr parent_joint = link->parent_joint;
00072   Eigen::Vector3f origin_x(0,0,1);
00073   Eigen::Vector3f dest_x(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z);
00074   Eigen::Quaternionf qua;
00075 
00076   qua.setFromTwoVectors(origin_x, dest_x);
00077   marker.pose.orientation.x = qua.x();
00078   marker.pose.orientation.y = qua.y();
00079   marker.pose.orientation.z = qua.z();
00080   marker.pose.orientation.w = qua.w();
00081 
00082   control.markers.push_back(marker);
00083   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00084   control.always_visible = true;
00085 
00086   int_marker.controls.push_back(control);
00087   return;
00088 }
00089 
00090 
00091 void UrdfModelMarker::addGraspPointControl(visualization_msgs::InteractiveMarker &int_marker, std::string link_frame_name_) {
00092   //yellow sphere
00093   visualization_msgs::InteractiveMarkerControl control;
00094   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00095   visualization_msgs::Marker marker;
00096   marker.type = visualization_msgs::Marker::SPHERE;
00097   marker.scale.x = 0.05;
00098   marker.scale.y = 0.05;
00099   marker.scale.z = 0.05;
00100 
00101   marker.color.a = 1.0;
00102   marker.color.r = 1.0;
00103   marker.color.g = 1.0;
00104   marker.color.b = 0.0;
00105 
00106   control.markers.push_back(marker);
00107   control.always_visible = true;
00108   int_marker.controls.push_back(control);
00109 
00110   if (linkMarkerMap[link_frame_name_].gp.displayMoveMarker) {
00111     im_helpers::add6DofControl(int_marker,false);
00112   }
00113 }
00114 
00115 
00116 void UrdfModelMarker::callSetDynamicTf(string parent_frame_id, string frame_id, geometry_msgs::Transform transform) {
00117   jsk_topic_tools::ScopedTimer timer = dynamic_tf_check_time_acc_.scopedTimer();
00118   dynamic_tf_publisher::SetDynamicTF SetTf;
00119   //SetTf.request.freq = 10;
00120   SetTf.request.freq = 20;
00121   //SetTf.request.freq = 100;
00122   SetTf.request.cur_tf.header.stamp = ros::Time::now();
00123   SetTf.request.cur_tf.header.frame_id = parent_frame_id;
00124   SetTf.request.cur_tf.child_frame_id = frame_id;
00125   SetTf.request.cur_tf.transform = transform;
00126   if (use_dynamic_tf_ || parent_frame_id == frame_id_) {
00127     //std::cout << parent_frame_id << frame_id << std::endl;
00128     dynamic_tf_publisher_client.call(SetTf);
00129   }
00130 }
00131 
00132 void UrdfModelMarker::callPublishTf() {
00133   if (use_dynamic_tf_) {
00134     std_srvs::Empty req;
00135     dynamic_tf_publisher_publish_tf_client.call(req);
00136   }
00137 }
00138 
00139 void UrdfModelMarker::publishBasePose(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00140   publishBasePose(feedback->pose, feedback->header);
00141 }
00142 
00143 void UrdfModelMarker::publishBasePose(geometry_msgs::Pose pose, std_msgs::Header header) {
00144   geometry_msgs::PoseStamped ps;
00145   ps.pose = pose;
00146   ps.header = header;
00147   pub_base_pose_.publish(ps);
00148 }
00149 
00150 
00151 
00152 void UrdfModelMarker::publishMarkerPose(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00153   publishMarkerPose(feedback->pose, feedback->header, feedback->marker_name);
00154 }
00155 
00156 void UrdfModelMarker::publishMarkerPose(geometry_msgs::Pose pose, std_msgs::Header header, std::string marker_name) {
00157   jsk_interactive_marker::MarkerPose mp;
00158   mp.pose.header = header;
00159   mp.pose.pose = pose;
00160   mp.marker_name = marker_name;
00161   mp.type = jsk_interactive_marker::MarkerPose::GENERAL;
00162   pub_.publish(mp);
00163 }
00164 
00165 
00166 void UrdfModelMarker::publishMarkerMenu(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int menu) {
00167   jsk_interactive_marker::MarkerMenu m;
00168   m.marker_name = feedback->marker_name;
00169   m.menu=menu;
00170   pub_move_.publish(m);
00171 }
00172 
00173 void UrdfModelMarker::publishMoveObject(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00174 
00175   //jsk_interactive_marker::MoveObject m;
00176   jsk_interactive_marker::MarkerMenu m;
00177   /*
00178     m.goal.pose.header = feedback->header;
00179     m.goal.pose.pose = feedback->pose;
00180 
00181     m.origin.pose.header = feedback->header;
00182     m.origin.pose.pose = linkMarkerMap[feedback->marker_name].origin;
00183 
00184     m.graspPose = linkMarkerMap[feedback->marker_name].gp.pose;
00185     pub_move_.publish(m);*/
00186 }
00187 
00188 void UrdfModelMarker::publishJointState(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00189   publishJointState();
00190 }
00191 
00192 void UrdfModelMarker::republishJointState(sensor_msgs::JointState js) {
00193   js.header.stamp = ros::Time::now();
00194   pub_joint_state_.publish(js);
00195 }
00196 
00197 void UrdfModelMarker::setRootPoseCB(const geometry_msgs::PoseStampedConstPtr &msg) {
00198   setRootPose(*msg);
00199 }
00200 void UrdfModelMarker::setRootPose (geometry_msgs::PoseStamped ps) {
00201   try {
00202     init_stamp_ = ps.header.stamp;
00203     tfl_.transformPose(frame_id_, ps, ps);
00204 
00205     geometry_msgs::Pose pose = getRootPose(ps.pose);
00206 
00207     string root_frame = tf_prefix_ + model->getRoot()->name;
00208     linkMarkerMap[frame_id_].pose = pose;
00209     callSetDynamicTf(frame_id_, root_frame, Pose2Transform(pose));
00210     root_pose_ = pose;
00211     addChildLinkNames(model->getRoot(), true, false);
00212     publishMarkerPose(pose, ps.header, root_frame);
00213     
00214   }
00215   catch (tf::TransformException ex) {
00216     ROS_ERROR("%s",ex.what());
00217   }
00218 
00219 }
00220 
00221 
00222 
00223 
00224 void UrdfModelMarker::resetJointStatesCB(const sensor_msgs::JointStateConstPtr &msg, bool update_root) {
00225   boost::mutex::scoped_lock lock(joint_states_mutex_);
00226   if (is_joint_states_locked_) {
00227     return;
00228   }
00229   jsk_topic_tools::ScopedTimer timer = reset_joint_states_check_time_acc_.scopedTimer();
00230   setJointState(model->getRoot(), msg);
00231   republishJointState(*msg);
00232 
00233   //update root correctly
00234   //this may take long time
00235   if (update_root) {
00236     callPublishTf();
00237     ros::spinOnce();
00238   }
00239   resetRootForVisualization();
00240   server_->applyChanges();
00241 }
00242 
00243 
00244 void UrdfModelMarker::proc_feedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, string parent_frame_id, string frame_id) {
00245   ROS_INFO("proc_feedback");
00246   switch (feedback->event_type) {
00247   case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
00248   case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
00249     linkMarkerMap[frame_id].pose = feedback->pose;
00250     //root link
00251     if (parent_frame_id == frame_id_) {
00252       root_pose_ = feedback->pose;
00253       publishBasePose(feedback);
00254     }
00255     callSetDynamicTf(parent_frame_id, frame_id, Pose2Transform(feedback->pose));
00256     publishMarkerPose(feedback);
00257     publishJointState(feedback);
00258     break;
00259   case visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK:
00260     cout << "clicked" << " frame:" << frame_id << mode_ << endl;
00261     //linkMarkerMap[frame_id].displayMoveMarker ^= true;
00262     if (mode_ != "visualization") {
00263       linkMarkerMap[linkMarkerMap[frame_id].movable_link].displayMoveMarker ^= true;
00264       addChildLinkNames(model->getRoot(), true, false);
00265     }
00266     else {
00267       geometry_msgs::PoseStamped ps = getOriginPoseStamped();
00268       pub_selected_.publish(ps);
00269       jsk_recognition_msgs::Int32Stamped index_msg;
00270       index_msg.data = index_;
00271       index_msg.header.stamp = init_stamp_;
00272       pub_selected_index_.publish(index_msg);
00273     }
00274     break;
00275 
00276   }
00277   diagnostic_updater_->update();
00278 }
00279 
00280 
00281 
00282 void UrdfModelMarker::graspPointCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00283   //linkMarkerMap[feedback->marker_name].gp.pose = feedback->pose;
00284   //publishMarkerPose(feedback);
00285   //publishMarkerMenu(feedback, jsk_interactive_marker::MarkerMenu::MOVE);
00286 
00287   KDL::Vector graspVec(feedback->mouse_point.x, feedback->mouse_point.y, feedback->mouse_point.z);
00288   KDL::Frame parentFrame;
00289   tf::poseMsgToKDL (linkMarkerMap[feedback->marker_name].pose, parentFrame);
00290 
00291   graspVec = parentFrame.Inverse(graspVec);
00292 
00293   geometry_msgs::Pose p;
00294   p.position.x = graspVec.x();
00295   p.position.y = graspVec.y();
00296   p.position.z = graspVec.z();
00297   p.orientation = linkMarkerMap[feedback->marker_name].gp.pose.orientation;
00298   linkMarkerMap[feedback->marker_name].gp.pose = p;
00299   
00300   linkMarkerMap[feedback->marker_name].gp.displayGraspPoint = true;
00301   addChildLinkNames(model->getRoot(), true, false);
00302   //addChildLinkNames(model->getRoot(), true, false, true, 0);
00303 }
00304 
00305 
00306 void UrdfModelMarker::jointMoveCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00307   publishJointState(feedback);
00308   sleep(0.5);
00309   publishMarkerMenu(feedback, jsk_interactive_marker::MarkerMenu::JOINT_MOVE);
00310 }
00311 
00312 void UrdfModelMarker::resetMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00313   
00314   publishJointState(feedback);
00315   publishMarkerMenu(feedback, jsk_interactive_marker::MarkerMenu::RESET_JOINT);
00316 }
00317 
00318 void UrdfModelMarker::resetBaseMsgCB(const std_msgs::EmptyConstPtr &msg) {
00319   resetBaseCB();
00320 }
00321 
00322 void UrdfModelMarker::resetBaseMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00323   resetBaseCB();
00324 }
00325 void UrdfModelMarker::resetBaseCB() {
00326   resetRobotBase();
00327 
00328   geometry_msgs::PoseStamped ps;
00329   ps.header.frame_id = frame_id_;
00330   ps.pose = root_pose_;
00331   setRootPose(ps);
00332 
00333   // to update root link marker
00334   addChildLinkNames(model->getRoot(), true, false);
00335 }
00336 
00337 void UrdfModelMarker::resetRobotBase() {
00338   //set root_pose_ to robot base pose
00339   try {
00340     tf::StampedTransform transform;
00341     geometry_msgs::TransformStamped ts_msg;
00342     tfl_.lookupTransform(frame_id_, model->getRoot()->name,
00343                          ros::Time(0), transform);
00344     tf::transformStampedTFToMsg(transform, ts_msg);
00345 
00346     root_pose_ = Transform2Pose(ts_msg.transform);
00347   }
00348   catch (tf::TransformException ex) {
00349     ROS_ERROR("%s",ex.what());
00350   }
00351 }
00352 
00353 void UrdfModelMarker::resetRootForVisualization() {
00354   if (fixed_link_.size() > 0 && (mode_ == "visualization" || mode_ == "robot")) {
00355     string marker_name =  tf_prefix_ + model->getRoot()->name;
00356     tf::StampedTransform st_offset;
00357     bool first_offset = true;
00358     for(int i=0; i<fixed_link_.size(); i++) {
00359       std::string link = fixed_link_[i];
00360       if (!link.empty()) {
00361         ROS_DEBUG_STREAM("fixed_link:" << tf_prefix_ + model->getRoot()->name << tf_prefix_ + link);
00362         const std::string source_frame = tf_prefix_ + link;
00363         const std::string target_frame = tf_prefix_ + model->getRoot()->name;
00364         try {
00365           tf::StampedTransform st_link_offset;
00366           ros::Time now = ros::Time(0);
00367           tfl_.waitForTransform(target_frame, source_frame, now, ros::Duration(5.0));
00368           tfl_.lookupTransform(target_frame, source_frame,
00369                                now, st_link_offset);
00370 
00371           if (first_offset) {
00372             st_offset.setRotation(st_link_offset.getRotation());
00373             st_offset.setOrigin(st_link_offset.getOrigin());
00374             first_offset = false;
00375           }
00376           else {
00377             st_offset.setRotation(st_link_offset.getRotation().slerp(st_offset.getRotation(), (i * 1.0)/(i + 1)));
00378             st_offset.setOrigin(st_link_offset.getOrigin().lerp(st_offset.getOrigin(), (i* 1.0)/(i+1)));
00379           }
00380         }
00381         catch (tf::TransformException ex) {
00382           ROS_ERROR("Failed to lookup transformation from %s to %s: %s",
00383                         source_frame.c_str(), target_frame.c_str(),
00384                         ex.what());
00385         }
00386       }
00387     }
00388 
00389     //multiply fixed_link_offset_
00390     tf::StampedTransform st_fixed_link_offset;
00391     geometry_msgs::TransformStamped ts_fixed_link_offset;
00392     ts_fixed_link_offset.transform.translation.x = fixed_link_offset_.position.x;
00393     ts_fixed_link_offset.transform.translation.y = fixed_link_offset_.position.y;
00394     ts_fixed_link_offset.transform.translation.z = fixed_link_offset_.position.z;
00395     ts_fixed_link_offset.transform.rotation = fixed_link_offset_.orientation;
00396 
00397     tf::transformStampedMsgToTF(ts_fixed_link_offset, st_fixed_link_offset);
00398 
00399     tf::Transform transform;
00400     transform = st_offset * st_fixed_link_offset;
00401 
00402     //convert to root_offset_
00403     geometry_msgs::Transform tf_msg;
00404     tf::transformTFToMsg(transform, tf_msg);
00405 
00406     root_offset_.position.x = tf_msg.translation.x;
00407     root_offset_.position.y = tf_msg.translation.y;
00408     root_offset_.position.z = tf_msg.translation.z;
00409     root_offset_.orientation = tf_msg.rotation;
00410 
00411     //reset root_pose_
00412     geometry_msgs::PoseStamped ps;
00413     ps.header.stamp = ros::Time::now();
00414     ps.header.frame_id = frame_id_;
00415     ps.pose.orientation.w = 1.0;
00416     //setRootPose(ps);
00417     root_pose_ = ps.pose;
00418 
00419     geometry_msgs::Pose pose = getRootPose(ps.pose);
00420 
00421     string root_frame = tf_prefix_ + model->getRoot()->name;
00422     linkMarkerMap[frame_id_].pose = pose;
00423     callSetDynamicTf(frame_id_, root_frame, Pose2Transform(pose));
00424 
00425     addChildLinkNames(model->getRoot(), true, false);
00426   }
00427 }
00428 
00429 
00430 
00431 
00432 void UrdfModelMarker::registrationCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00433   
00434   publishJointState(feedback);
00435 }
00436 
00437 void UrdfModelMarker::moveCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00438   /* publish jsk_interactive_marker::MoveModel */
00439   jsk_interactive_marker::MoveModel mm;
00440   mm.header = feedback->header;
00441   mm.name = model_name_;
00442   mm.description = model_description_;
00443   mm.joint_state_origin = joint_state_origin_;
00444   mm.joint_state_goal = joint_state_;
00445   mm.pose_origin.header.frame_id = frame_id_;
00446   mm.pose_origin.pose = root_pose_origin_;
00447   mm.pose_goal.header.frame_id = frame_id_;
00448   mm.pose_goal.pose = root_pose_;
00449   pub_move_model_.publish(mm);
00450 
00451 
00452   /* publish jsk_interactive_marker::MoveObject */
00453   jsk_interactive_marker::MoveObject mo;
00454   mo.origin.header = feedback->header;
00455   mo.origin.pose = linkMarkerMap[feedback->marker_name].origin;
00456 
00457   mo.goal.header = feedback->header;
00458   mo.goal.pose = feedback->pose;
00459 
00460   mo.graspPose = linkMarkerMap[feedback->marker_name].gp.pose;
00461   pub_move_object_.publish(mo);
00462 
00463 }
00464 
00465 void UrdfModelMarker::setPoseCB() {
00466   cout << "setPose" <<endl;
00467   joint_state_origin_ = joint_state_;
00468   root_pose_origin_ = root_pose_;
00469   setOriginalPose(model->getRoot());
00470 }
00471 
00472 void UrdfModelMarker::setPoseCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00473   setPoseCB();
00474 }
00475 
00476 void UrdfModelMarker::hideMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00477   linkMarkerMap[linkMarkerMap[feedback->marker_name].movable_link].displayMoveMarker = false;
00478   addChildLinkNames(model->getRoot(), true, false);
00479 }
00480 
00481 void UrdfModelMarker::hideAllMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00482   map<string, linkProperty>::iterator it = linkMarkerMap.begin();
00483   while (it != linkMarkerMap.end())
00484   {
00485     (*it).second.displayMoveMarker = false;
00486     ++it;
00487   }
00488   addChildLinkNames(model->getRoot(), true, false);
00489 }
00490 
00491 void UrdfModelMarker::hideModelMarkerCB(const std_msgs::EmptyConstPtr &msg) {
00492   map<string, linkProperty>::iterator it = linkMarkerMap.begin();
00493   while (it != linkMarkerMap.end())
00494   {
00495     (*it).second.displayModelMarker = false;
00496     ++it;
00497   }
00498   addChildLinkNames(model->getRoot(), true, false);
00499 }
00500 
00501 void UrdfModelMarker::showModelMarkerCB(const std_msgs::EmptyConstPtr &msg) {
00502   map<string, linkProperty>::iterator it = linkMarkerMap.begin();
00503   while (it != linkMarkerMap.end())
00504   {
00505     (*it).second.displayModelMarker = true;
00506     ++it;
00507   }
00508   addChildLinkNames(model->getRoot(), true, false);
00509 
00510 }
00511 
00512 void UrdfModelMarker::setUrdfCB(const std_msgs::StringConstPtr &msg) {
00513   //clear
00514   server_->clear();
00515   linkMarkerMap.clear();
00516 
00517   model = parseURDF(msg->data);
00518   if (!model) {
00519     ROS_ERROR("Model Parsing the xml failed");
00520     return;
00521   }
00522   addChildLinkNames(model->getRoot(), true, true);
00523 
00524   // start JointState
00525   publishJointState();
00526   return;
00527 }
00528 
00529 
00530 void UrdfModelMarker::graspPoint_feedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, string link_name) {
00531   switch (feedback->event_type) {
00532   case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
00533     linkMarkerMap[link_name].gp.pose = feedback->pose;
00534     publishMarkerPose(feedback);
00535     break;
00536   case visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK:
00537     cout << "clicked" << " frame:" << feedback->marker_name << endl;
00538     linkMarkerMap[link_name].gp.displayMoveMarker ^= true;
00539     addChildLinkNames(model->getRoot(), true, false);
00540     break;
00541   }
00542 }
00543 
00544 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) {
00545   visualization_msgs::Marker meshMarker;
00546 
00547   if (use_color) meshMarker.color = color;
00548   meshMarker.mesh_resource = mesh_resource;
00549   meshMarker.mesh_use_embedded_materials = !use_color;
00550   meshMarker.type = visualization_msgs::Marker::MESH_RESOURCE;
00551   
00552   meshMarker.scale = scale;
00553   meshMarker.pose = stamped.pose;
00554   visualization_msgs::InteractiveMarkerControl control;
00555   control.markers.push_back(meshMarker);
00556   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00557   control.always_visible = true;
00558   
00559   return control;
00560 }
00561 
00562 visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeMeshMarkerControl(const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale)
00563 {
00564   std_msgs::ColorRGBA color;
00565   color.r = 0;
00566   color.g = 0;
00567   color.b = 0;
00568   color.a = 0;
00569   //color.a = 0.3;
00570   return makeMeshMarkerControl(mesh_resource, stamped, scale, color, false);
00571   //return makeMeshMarkerControl(mesh_resource, stamped, scale, color, true);
00572 }
00573 
00574 visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeMeshMarkerControl(const std::string &mesh_resource,
00575                                                                                     const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color)
00576 {
00577   return makeMeshMarkerControl(mesh_resource, stamped, scale, color, true);
00578 }
00579 
00580 visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeCylinderMarkerControl(const geometry_msgs::PoseStamped &stamped, double length,  double radius, const std_msgs::ColorRGBA &color, bool use_color) {
00581   visualization_msgs::Marker cylinderMarker;
00582 
00583   if (use_color) cylinderMarker.color = color;
00584   cylinderMarker.type = visualization_msgs::Marker::CYLINDER;
00585   cylinderMarker.scale.x = radius * 2;
00586   cylinderMarker.scale.y = radius * 2;
00587   cylinderMarker.scale.z = length;
00588   cylinderMarker.pose = stamped.pose;
00589 
00590   visualization_msgs::InteractiveMarkerControl control;
00591   control.markers.push_back(cylinderMarker);
00592   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00593   control.always_visible = true;
00594 
00595   return control;
00596 }
00597 
00598 visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeBoxMarkerControl(const geometry_msgs::PoseStamped &stamped, Vector3 dim, const std_msgs::ColorRGBA &color, bool use_color) {
00599   visualization_msgs::Marker boxMarker;
00600 
00601   fprintf(stderr, "urdfModelMarker = %f %f %f\n", dim.x, dim.y, dim.z);
00602   if (use_color) boxMarker.color = color;
00603   boxMarker.type = visualization_msgs::Marker::CUBE;
00604   boxMarker.scale.x = dim.x;
00605   boxMarker.scale.y = dim.y;
00606   boxMarker.scale.z = dim.z;
00607   boxMarker.pose = stamped.pose;
00608 
00609   visualization_msgs::InteractiveMarkerControl control;
00610   control.markers.push_back(boxMarker);
00611   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00612   control.always_visible = true;
00613 
00614   return control;
00615 }
00616 
00617 visualization_msgs::InteractiveMarkerControl UrdfModelMarker::makeSphereMarkerControl(const geometry_msgs::PoseStamped &stamped, double rad, const std_msgs::ColorRGBA &color, bool use_color) {
00618   visualization_msgs::Marker sphereMarker;
00619 
00620   if (use_color) sphereMarker.color = color;
00621   sphereMarker.type = visualization_msgs::Marker::SPHERE;
00622   sphereMarker.scale.x = rad * 2;
00623   sphereMarker.scale.y = rad * 2;
00624   sphereMarker.scale.z = rad * 2;
00625   sphereMarker.pose = stamped.pose;
00626 
00627   visualization_msgs::InteractiveMarkerControl control;
00628   control.markers.push_back(sphereMarker);
00629   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00630   control.always_visible = true;
00631 
00632   return control;
00633 }
00634 
00635 void UrdfModelMarker::publishJointState() {
00636   getJointState();
00637   pub_joint_state_.publish(joint_state_);
00638 }
00639 
00640 void UrdfModelMarker::getJointState() {
00641   sensor_msgs::JointState new_joint_state;
00642   joint_state_ = new_joint_state;
00643   joint_state_.header.stamp = ros::Time::now();
00644   getJointState(model->getRoot());
00645 }
00646 
00647 void UrdfModelMarker::getJointState(LinkConstSharedPtr link)
00648 {
00649   string link_frame_name_ =  tf_prefix_ + link->name;
00650   JointSharedPtr parent_joint = link->parent_joint;
00651   if (parent_joint != NULL) {
00652     KDL::Frame initialFrame;
00653     KDL::Frame presentFrame;
00654     KDL::Rotation rot;
00655     KDL::Vector rotVec;
00656     KDL::Vector jointVec;
00657     double jointAngle;
00658     double jointAngleAllRange;
00659     switch(parent_joint->type) {
00660     case Joint::REVOLUTE:
00661     case Joint::CONTINUOUS:
00662     {
00663       linkProperty *link_property = &linkMarkerMap[link_frame_name_];
00664       tf::poseMsgToKDL (link_property->initial_pose, initialFrame);
00665       tf::poseMsgToKDL (link_property->pose, presentFrame);
00666       rot = initialFrame.M.Inverse() * presentFrame.M;
00667       jointAngle = rot.GetRotAngle(rotVec);
00668       jointVec = KDL::Vector(link_property->joint_axis.x,
00669                              link_property->joint_axis.y,
00670                              link_property->joint_axis.z);
00671       if (KDL::dot(rotVec,jointVec) < 0) {
00672         jointAngle = - jointAngle;
00673       }
00674       if (link_property->joint_angle > M_PI/2 && jointAngle < -M_PI/2) {
00675         link_property->rotation_count += 1;
00676       }
00677       else if (link_property->joint_angle < -M_PI/2 && jointAngle > M_PI/2) {
00678         link_property->rotation_count -= 1;
00679       }
00680       link_property->joint_angle = jointAngle;
00681       jointAngleAllRange = jointAngle + link_property->rotation_count * M_PI * 2;
00682 
00683       if (parent_joint->type == Joint::REVOLUTE && parent_joint->limits != NULL) {
00684         bool changeMarkerAngle = false;
00685         if (jointAngleAllRange < parent_joint->limits->lower) {
00686           jointAngleAllRange = parent_joint->limits->lower + 0.001;
00687           changeMarkerAngle = true;
00688         }
00689         if (jointAngleAllRange > parent_joint->limits->upper) {
00690           jointAngleAllRange = parent_joint->limits->upper - 0.001;
00691           changeMarkerAngle = true;
00692         }
00693 
00694         if (changeMarkerAngle) {
00695           setJointAngle(link, jointAngleAllRange);
00696         }
00697       }
00698 
00699       joint_state_.position.push_back(jointAngleAllRange);
00700       joint_state_.name.push_back(parent_joint->name);
00701       break;
00702     }
00703     case Joint::PRISMATIC:
00704     {
00705       KDL::Vector pos;
00706       linkProperty *link_property = &linkMarkerMap[link_frame_name_];
00707       tf::poseMsgToKDL (link_property->initial_pose, initialFrame);
00708       tf::poseMsgToKDL (link_property->pose, presentFrame);
00709 
00710       pos = presentFrame.p - initialFrame.p;
00711 
00712       jointVec = KDL::Vector(link_property->joint_axis.x,
00713                              link_property->joint_axis.y,
00714                              link_property->joint_axis.z);
00715       jointVec = jointVec / jointVec.Norm(); // normalize vector
00716       jointAngle = KDL::dot(jointVec, pos);
00717 
00718       link_property->joint_angle = jointAngle;
00719       jointAngleAllRange = jointAngle;
00720 
00721       if (parent_joint->type == Joint::PRISMATIC && parent_joint->limits != NULL) {
00722         bool changeMarkerAngle = false;
00723         if (jointAngleAllRange < parent_joint->limits->lower) {
00724           jointAngleAllRange = parent_joint->limits->lower + 0.003;
00725           changeMarkerAngle = true;
00726         }
00727         if (jointAngleAllRange > parent_joint->limits->upper) {
00728           jointAngleAllRange = parent_joint->limits->upper - 0.003;
00729           changeMarkerAngle = true;
00730         }
00731         if (changeMarkerAngle) {
00732           setJointAngle(link, jointAngleAllRange);
00733         }
00734       }
00735 
00736       joint_state_.position.push_back(jointAngleAllRange);
00737       joint_state_.name.push_back(parent_joint->name);
00738       break;
00739     }
00740     case Joint::FIXED:
00741       break;
00742     default:
00743       break;
00744     }
00745     server_->applyChanges();
00746   }
00747 
00748   for (std::vector<LinkSharedPtr >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) {
00749     getJointState(*child);
00750   }
00751   return;
00752 }
00753 
00754 void UrdfModelMarker::setJointAngle(LinkConstSharedPtr link, double joint_angle) {
00755   string link_frame_name_ =  tf_prefix_ + link->name;
00756   JointSharedPtr parent_joint = link->parent_joint;
00757 
00758   if (parent_joint == NULL) {
00759     return;
00760   }
00761 
00762   KDL::Frame initialFrame;
00763   KDL::Frame presentFrame;
00764   KDL::Rotation rot;
00765   KDL::Vector rotVec;
00766   KDL::Vector jointVec;
00767 
00768   std_msgs::Header link_header;
00769 
00770   int rotation_count = 0;
00771   
00772   switch(parent_joint->type) {
00773   case Joint::REVOLUTE:
00774   case Joint::CONTINUOUS:
00775   {
00776     if (joint_angle > M_PI) {
00777       rotation_count = (int)((joint_angle + M_PI) / (M_PI * 2));
00778       joint_angle -= rotation_count * M_PI * 2;
00779     }
00780     else if (joint_angle < -M_PI) {
00781       rotation_count = (int)((- joint_angle + M_PI) / (M_PI * 2));
00782       joint_angle -= rotation_count * M_PI * 2;
00783     }
00784     linkProperty *link_property = &linkMarkerMap[link_frame_name_];
00785     link_property->joint_angle = joint_angle;
00786     link_property->rotation_count = rotation_count;
00787 
00788     tf::poseMsgToKDL (link_property->initial_pose, initialFrame);
00789     tf::poseMsgToKDL (link_property->initial_pose, presentFrame);
00790     jointVec = KDL::Vector(link_property->joint_axis.x,
00791                            link_property->joint_axis.y,
00792                            link_property->joint_axis.z);
00793 
00794     presentFrame.M = KDL::Rotation::Rot(jointVec, joint_angle) * initialFrame.M;
00795     tf::poseKDLToMsg(presentFrame, link_property->pose);
00796 
00797     break;
00798   }
00799   case Joint::PRISMATIC:
00800   {
00801     linkProperty *link_property = &linkMarkerMap[link_frame_name_];
00802     link_property->joint_angle = joint_angle;
00803     link_property->rotation_count = rotation_count;
00804     tf::poseMsgToKDL (link_property->initial_pose, initialFrame);
00805     tf::poseMsgToKDL (link_property->initial_pose, presentFrame);
00806     jointVec = KDL::Vector(link_property->joint_axis.x,
00807                            link_property->joint_axis.y,
00808                            link_property->joint_axis.z);
00809     jointVec = jointVec / jointVec.Norm(); // normalize vector
00810     presentFrame.p = joint_angle * jointVec + initialFrame.p;
00811     tf::poseKDLToMsg(presentFrame, link_property->pose);
00812     break;
00813   }
00814   default:
00815     break;
00816   }
00817 
00818   link_header.stamp = ros::Time(0);
00819   link_header.frame_id = linkMarkerMap[link_frame_name_].frame_id;
00820 
00821   server_->setPose(link_frame_name_, linkMarkerMap[link_frame_name_].pose, link_header);
00822   //server_->applyChanges();
00823   callSetDynamicTf(linkMarkerMap[link_frame_name_].frame_id, link_frame_name_, Pose2Transform(linkMarkerMap[link_frame_name_].pose));
00824 }
00825 
00826 void UrdfModelMarker::setJointState(LinkConstSharedPtr link, const sensor_msgs::JointStateConstPtr &js)
00827 {
00828   string link_frame_name_ =  tf_prefix_ + link->name;
00829   JointSharedPtr parent_joint = link->parent_joint;
00830   if (parent_joint != NULL) {
00831     KDL::Frame initialFrame;
00832     KDL::Frame presentFrame;
00833     KDL::Rotation rot;
00834     KDL::Vector rotVec;
00835     KDL::Vector jointVec;
00836     double jointAngle;
00837     bool changeAngle = false;
00838     std_msgs::Header link_header;
00839     switch(parent_joint->type) {
00840     case Joint::REVOLUTE:
00841     case Joint::CONTINUOUS:
00842       for(int i=0; i< js->name.size(); i++) {
00843         if (js->name[i] == parent_joint->name) {
00844           jointAngle = js->position[i];
00845           changeAngle = true;
00846           break;
00847         }
00848       }
00849       if (!changeAngle) {
00850         break;
00851       }
00852       setJointAngle(link, jointAngle);
00853       break;
00854     case Joint::PRISMATIC:
00855       for(int i=0; i< js->name.size(); i++) {
00856         if (js->name[i] == parent_joint->name) {
00857           jointAngle = js->position[i];
00858           changeAngle = true;
00859           break;
00860         }
00861       }
00862       if (!changeAngle) {
00863         break;
00864       }
00865       setJointAngle(link, jointAngle);
00866       break;
00867     default:
00868       break;
00869     }
00870   }
00871   for (std::vector<LinkSharedPtr >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) {
00872     setJointState(*child, js);
00873   }
00874   return;
00875 }
00876 
00877 geometry_msgs::Pose UrdfModelMarker::getRootPose(geometry_msgs::Pose pose) {
00878   KDL::Frame pose_frame, offset_frame;
00879   tf::poseMsgToKDL(pose, pose_frame);
00880   tf::poseMsgToKDL(root_offset_, offset_frame);
00881   pose_frame = pose_frame * offset_frame.Inverse();
00882   tf::poseKDLToMsg(pose_frame, pose);
00883   return pose;
00884 }
00885 
00886 geometry_msgs::PoseStamped UrdfModelMarker::getOriginPoseStamped() {
00887   geometry_msgs::PoseStamped ps;
00888   geometry_msgs::Pose pose;
00889   pose = root_pose_;
00890   KDL::Frame pose_frame, offset_frame;
00891   tf::poseMsgToKDL(pose, pose_frame);
00892   tf::poseMsgToKDL(root_offset_, offset_frame);
00893   pose_frame = pose_frame * offset_frame;
00894   tf::poseKDLToMsg(pose_frame, pose);
00895   ps.pose = pose;
00896   ps.header.frame_id = frame_id_;
00897   ps.header.stamp = init_stamp_;
00898   return ps;
00899 }
00900 
00901 
00902 void UrdfModelMarker::setOriginalPose(LinkConstSharedPtr link)
00903 {
00904   string link_frame_name_ =  tf_prefix_ + link->name;
00905   linkMarkerMap[link_frame_name_].origin =  linkMarkerMap[link_frame_name_].pose;
00906   
00907   for (std::vector<LinkSharedPtr >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) {
00908     setOriginalPose(*child);
00909   }
00910 }
00911 
00912 void UrdfModelMarker::addChildLinkNames(LinkConstSharedPtr link, bool root, bool init) {
00913   //addChildLinkNames(link, root, init, false, 0);
00914   addChildLinkNames(link, root, init, use_visible_color_, 0);
00915 }
00916 
00917 void UrdfModelMarker::addChildLinkNames(LinkConstSharedPtr link, bool root, bool init, bool use_color, int color_index)
00918 {
00919   geometry_msgs::PoseStamped ps;
00920 
00921   double scale_factor = 1.02;
00922   string link_frame_name_ =  tf_prefix_ + link->name;
00923   string parent_link_frame_name_;
00924   ROS_INFO("link_frame_name: %s", link_frame_name_.c_str());
00925   if (root) {
00926     parent_link_frame_name_ = frame_id_;
00927     //ps.pose = root_pose_;
00928     ps.pose = getRootPose(root_pose_);
00929   }
00930   else {
00931     parent_link_frame_name_ = link->parent_joint->parent_link_name;
00932     parent_link_frame_name_ = tf_prefix_ + parent_link_frame_name_;
00933     ps.pose = UrdfPose2Pose(link->parent_joint->parent_to_joint_origin_transform);
00934   }
00935   ps.header.frame_id =  parent_link_frame_name_;
00936   ps.header.stamp = ros::Time(0);
00937 
00938   //initialize linkProperty
00939   if (init) {
00940     callSetDynamicTf(parent_link_frame_name_, link_frame_name_, Pose2Transform(ps.pose));
00941     linkProperty lp;
00942     lp.pose = ps.pose;
00943     lp.origin = ps.pose;
00944     lp.initial_pose = ps.pose;
00945     if (link->parent_joint !=NULL) {
00946       lp.joint_axis = link->parent_joint->axis;
00947     }
00948     lp.joint_angle = 0;
00949     lp.rotation_count=0;
00950     if (link->parent_joint !=NULL && link->parent_joint->type == Joint::FIXED) {
00951       lp.movable_link = linkMarkerMap[parent_link_frame_name_].movable_link;
00952     }
00953     else {
00954       lp.movable_link = link_frame_name_;
00955     }
00956 
00957     linkMarkerMap.insert(map<string, linkProperty>::value_type(link_frame_name_, lp));
00958   }
00959 
00960   linkMarkerMap[link_frame_name_].frame_id = parent_link_frame_name_;
00961 
00962   visualization_msgs::InteractiveMarker int_marker;
00963   int_marker.header = ps.header;
00964 
00965   int_marker.name = link_frame_name_;
00966   if (root) {
00967     int_marker.description = model_description_;
00968   }
00969   int_marker.scale = 1.0;
00970   int_marker.pose = ps.pose;
00971 
00972 
00973   if (!init && !root) {
00974     visualization_msgs::InteractiveMarker old_marker;
00975     if (server_->get(link_frame_name_, old_marker)) {
00976       int_marker.pose = old_marker.pose;
00977     }
00978   }
00979 
00980 
00981   //hide marker
00982   if (!linkMarkerMap[link_frame_name_].displayModelMarker) {
00983     server_->erase(link_frame_name_);
00984     server_->erase(tf_prefix_ + link->name + "/grasp"); //grasp marker
00985   }
00986   else {
00987 
00988     //move Marker
00989     if (linkMarkerMap[link_frame_name_].displayMoveMarker) {
00990       addMoveMarkerControl(int_marker, link, root);
00991     }
00992     //model Mesh Marker
00993     std_msgs::ColorRGBA color;
00994     if (mode_ == "visualization") {
00995       color.r = (double)0xFF / 0xFF;
00996       color.g = (double)0xFF / 0xFF;
00997       color.b = (double)0x00 / 0xFF;
00998       color.a = 0.5;
00999     }
01000     else {
01001       switch(color_index %3) {
01002       case 0:
01003         color.r = (double)0xFF / 0xFF;
01004         color.g = (double)0xC3 / 0xFF;
01005         color.b = (double)0x00 / 0xFF;
01006         break;
01007       case 1:
01008         color.r = (double)0x58 / 0xFF;
01009         color.g = (double)0x0E / 0xFF;
01010         color.b = (double)0xAD / 0xFF;
01011         break;
01012       case 2:
01013         color.r = (double)0x0C / 0xFF;
01014         color.g = (double)0x5A / 0xFF;
01015         color.b = (double)0xA6 / 0xFF;
01016         break;
01017       }
01018       color.a = 1.0;
01019     }
01020 
01021     //link_array
01022     std::vector<VisualSharedPtr > visual_array;
01023     if (link->visual_array.size() != 0) {
01024       visual_array = link->visual_array;
01025     }
01026     else if (link->visual.get() != NULL) {
01027       visual_array.push_back(link->visual);
01028     }
01029     for(int i=0; i<visual_array.size(); i++) {
01030       VisualSharedPtr link_visual = visual_array[i];
01031       if (link_visual.get() != NULL && link_visual->geometry.get() != NULL) {
01032         visualization_msgs::InteractiveMarkerControl meshControl;
01033         if (link_visual->geometry->type == Geometry::MESH) {
01034 #if ROS_VERSION_MINIMUM(1,14,0) // melodic
01035           MeshConstSharedPtr mesh = std::static_pointer_cast<const Mesh>(link_visual->geometry);
01036 #else
01037           MeshConstSharedPtr mesh = boost::static_pointer_cast<const Mesh>(link_visual->geometry);
01038 #endif
01039           string model_mesh_ = mesh->filename;
01040           if (linkMarkerMap[link_frame_name_].mesh_file == "") {
01041             model_mesh_ = getRosPathFromModelPath(model_mesh_);
01042             linkMarkerMap[link_frame_name_].mesh_file = model_mesh_;
01043           }
01044           else {
01045             model_mesh_ = linkMarkerMap[link_frame_name_].mesh_file;
01046           }
01047           ps.pose = UrdfPose2Pose(link_visual->origin);
01048           ROS_DEBUG_STREAM("mesh_file:" << model_mesh_);
01049           geometry_msgs::Vector3 mesh_scale;
01050           mesh_scale.x = mesh->scale.x;
01051           mesh_scale.y = mesh->scale.y;
01052           mesh_scale.z = mesh->scale.z;
01053           ROS_INFO("make mesh marker from %s", model_mesh_.c_str());
01054           if (use_color) {
01055             meshControl = makeMeshMarkerControl(model_mesh_, ps, mesh_scale, color);
01056           }
01057           else {
01058             meshControl = makeMeshMarkerControl(model_mesh_, ps, mesh_scale);
01059           }
01060         }
01061         else if (link_visual->geometry->type == Geometry::CYLINDER) {
01062 #if ROS_VERSION_MINIMUM(1,14,0) // melodic
01063           CylinderConstSharedPtr cylinder = std::static_pointer_cast<const Cylinder>(link_visual->geometry);
01064 #else
01065           CylinderConstSharedPtr cylinder = boost::static_pointer_cast<const Cylinder>(link_visual->geometry);
01066 #endif
01067           ps.pose = UrdfPose2Pose(link_visual->origin);
01068           double length = cylinder->length;
01069           double radius = cylinder->radius;
01070           ROS_INFO_STREAM("cylinder " << link->name << ", length =  " << length << ", radius " << radius);
01071           if (use_color) {
01072             meshControl = makeCylinderMarkerControl(ps, length, radius, color, true);
01073           }
01074           else {
01075             meshControl = makeCylinderMarkerControl(ps, length, radius, color, true);
01076           }
01077         }
01078         else if (link_visual->geometry->type == Geometry::BOX) {
01079 #if ROS_VERSION_MINIMUM(1,14,0) // melodic
01080           BoxConstSharedPtr box = std::static_pointer_cast<const Box>(link_visual->geometry);
01081 #else
01082           BoxConstSharedPtr box = boost::static_pointer_cast<const Box>(link_visual->geometry);
01083 #endif
01084           ps.pose = UrdfPose2Pose(link_visual->origin);
01085           Vector3 dim = box->dim;
01086           ROS_INFO_STREAM("box " << link->name << ", dim =  " << dim.x << ", " << dim.y << ", " << dim.z);
01087           if (use_color) {
01088             meshControl = makeBoxMarkerControl(ps, dim, color, true);
01089           }
01090           else {
01091             meshControl = makeBoxMarkerControl(ps, dim, color, true);
01092           }
01093         }
01094         else if (link_visual->geometry->type == Geometry::SPHERE) {
01095 #if ROS_VERSION_MINIMUM(1,14,0) // melodic
01096           SphereConstSharedPtr sphere = std::static_pointer_cast<const Sphere>(link_visual->geometry);
01097 #else
01098           SphereConstSharedPtr sphere = boost::static_pointer_cast<const Sphere>(link_visual->geometry);
01099 #endif
01100           ps.pose = UrdfPose2Pose(link_visual->origin);
01101           double rad = sphere->radius;
01102           if (use_color) {
01103             meshControl = makeSphereMarkerControl(ps, rad, color, true);
01104           }
01105           else {
01106             meshControl = makeSphereMarkerControl(ps, rad, color, true);
01107           }
01108         }
01109         int_marker.controls.push_back(meshControl);
01110 
01111         server_->insert(int_marker);
01112         server_->setCallback(int_marker.name,
01113                               boost::bind(&UrdfModelMarker::proc_feedback, this, _1, parent_link_frame_name_, link_frame_name_));
01114 
01115         model_menu_.apply(*server_, link_frame_name_);
01116 
01117       }
01118       else {
01119         JointSharedPtr parent_joint = link->parent_joint;
01120         if (parent_joint != NULL) {
01121           if (parent_joint->type==Joint::REVOLUTE || parent_joint->type==Joint::REVOLUTE) {
01122             addInvisibleMeshMarkerControl(int_marker, link, color);
01123             server_->insert(int_marker);
01124             server_->setCallback(int_marker.name,
01125                                   boost::bind(&UrdfModelMarker::proc_feedback, this, _1, parent_link_frame_name_, link_frame_name_));
01126             model_menu_.apply(*server_, link_frame_name_);
01127           }
01128         }
01129       }
01130     }
01131     if (!robot_mode_) {
01132       //add Grasp Point Marker
01133       if (linkMarkerMap[link_frame_name_].gp.displayGraspPoint) {
01134         visualization_msgs::InteractiveMarker grasp_int_marker;
01135         double grasp_scale_factor = 1.02;
01136         string grasp_link_frame_name_ = tf_prefix_ + link->name + "/grasp";
01137         string grasp_parent_link_frame_name_ = tf_prefix_ + link->name;
01138 
01139         geometry_msgs::PoseStamped grasp_ps;
01140         grasp_ps.pose = linkMarkerMap[link_frame_name_].gp.pose;
01141         grasp_ps.header.frame_id =  grasp_parent_link_frame_name_;
01142 
01143         grasp_int_marker.header = grasp_ps.header;
01144         grasp_int_marker.name = grasp_link_frame_name_;
01145         grasp_int_marker.scale = grasp_scale_factor;
01146         grasp_int_marker.pose = grasp_ps.pose;
01147 
01148         addGraspPointControl(grasp_int_marker, link_frame_name_);
01149 
01150         server_->insert(grasp_int_marker);
01151         server_->setCallback(grasp_int_marker.name,
01152                               boost::bind(&UrdfModelMarker::graspPoint_feedback, this, _1, link_frame_name_));
01153 
01154       }
01155     }
01156   }
01157 
01158   //initialize JointState
01159   if (init) {
01160     if (!root && initial_pose_map_.count(link->parent_joint->name) != 0) {
01161       setJointAngle(link, initial_pose_map_[link->parent_joint->name]);
01162     }
01163   }
01164 
01165   //  cout << "Link:" << link->name << endl;
01166 
01167   for (std::vector<LinkSharedPtr >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) {
01168     addChildLinkNames(*child, false, init, use_color, color_index + 1);
01169   }
01170   if (root) {
01171     server_->applyChanges();
01172   }
01173 }
01174 
01175 
01176 
01177 UrdfModelMarker::UrdfModelMarker ()
01178 {}
01179 
01180 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) {
01181   diagnostic_updater_.reset(new diagnostic_updater::Updater);
01182   diagnostic_updater_->setHardwareID(ros::this_node::getName());
01183   diagnostic_updater_->add("Modeling Stats", boost::bind(&UrdfModelMarker::updateDiagnostic, this, _1));
01184 
01185   pnh_.param("server_name", server_name, std::string (""));
01186 
01187   if (server_name == "") {
01188     server_name = ros::this_node::getName();
01189   }
01190 
01191   pnh_.getParam("use_dynamic_tf", use_dynamic_tf_);
01192   if (use_dynamic_tf_) {
01193     ros::service::waitForService("set_dynamic_tf", -1);
01194     dynamic_tf_publisher_client = nh_.serviceClient<dynamic_tf_publisher::SetDynamicTF>("set_dynamic_tf", true);
01195     ros::service::waitForService("publish_tf", -1);
01196     dynamic_tf_publisher_publish_tf_client = nh_.serviceClient<std_srvs::Empty>("publish_tf", true);
01197   }
01198   ROS_INFO_STREAM("use_dynamic_tf_ is " << use_dynamic_tf_);
01199 
01200   if (index != -1) {
01201     stringstream ss;
01202     ss << model_name << index;
01203     model_name_ = ss.str();
01204   }
01205   else {
01206     model_name_ = model_name;
01207   }
01208 
01209   model_description_ = model_description;
01210   server_ = server;
01211   model_file_ = model_file;
01212   frame_id_ = frame_id;
01213   root_offset_ = root_offset;
01214   fixed_link_offset_ = root_offset;
01215   root_pose_ = root_pose.pose;
01216   init_stamp_ = root_pose.header.stamp;
01217   scale_factor_ = scale_factor;
01218   robot_mode_ = robot_mode;
01219   registration_ = registration;
01220   mode_ = mode;
01221   fixed_link_ = fixed_link;
01222   use_robot_description_ = use_robot_description;
01223   use_visible_color_ = use_visible_color;
01224   tf_prefix_ = server_name + "/" + model_name_ + "/";
01225   initial_pose_map_ = initial_pose_map;
01226   index_ = index;
01227 
01228   pub_ =  pnh_.advertise<jsk_interactive_marker::MarkerPose> ("pose", 1);
01229   pub_move_ =  pnh_.advertise<jsk_interactive_marker::MarkerMenu> ("marker_menu", 1);
01230   pub_move_object_ =  pnh_.advertise<jsk_interactive_marker::MoveObject> ("move_object", 1);
01231   pub_move_model_ =  pnh_.advertise<jsk_interactive_marker::MoveModel> ("move_model", 1);
01232   pub_selected_ =  pnh_.advertise<geometry_msgs::PoseStamped> (model_name + "/selected", 1);
01233   pub_selected_index_ =  pnh_.advertise<jsk_recognition_msgs::Int32Stamped> (model_name + "/selected_index", 1);
01234   pub_joint_state_ =  pnh_.advertise<sensor_msgs::JointState> (model_name_ + "/joint_states", 1);
01235   
01236   sub_set_root_pose_ = pnh_.subscribe<geometry_msgs::PoseStamped> (model_name_ + "/set_pose", 1, boost::bind(&UrdfModelMarker::setRootPoseCB, this, _1));
01237   sub_reset_joints_ = pnh_.subscribe<sensor_msgs::JointState> (model_name_ + "/reset_joint_states", 1, boost::bind(&UrdfModelMarker::resetJointStatesCB, this, _1, false));
01238   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));
01239   
01240   hide_marker_ = pnh_.subscribe<std_msgs::Empty> (model_name_ + "/hide_marker", 1, boost::bind(&UrdfModelMarker::hideModelMarkerCB, this, _1));
01241   show_marker_ = pnh_.subscribe<std_msgs::Empty> (model_name_ + "/show_marker", 1, boost::bind(&UrdfModelMarker::showModelMarkerCB, this, _1));
01242   sub_set_urdf_ = pnh_.subscribe<std_msgs::String>(model_name_ + "/set_urdf", 1, boost::bind(&UrdfModelMarker::setUrdfCB, this, _1));
01243 
01244   show_marker_ = pnh_.subscribe<std_msgs::Empty> (model_name_ + "/reset_root_pose", 1, boost::bind(&UrdfModelMarker::resetBaseMsgCB, this, _1));
01245 
01246   pub_base_pose_ = pnh_.advertise<geometry_msgs::PoseStamped>(model_name_ + "/base_pose", 1);
01247 
01248 
01249 
01250   /*
01251     serv_set_ = pnh_.advertiseService("set_pose",
01252     &InteractiveMarkerInterface::set_cb, this);
01253     serv_markers_set_ = pnh_.advertiseService("set_markers",
01254     &InteractiveMarkerInterface::markers_set_cb, this);
01255     serv_markers_del_ = pnh_.advertiseService("del_markers",
01256     &InteractiveMarkerInterface::markers_del_cb, this);
01257     serv_reset_ = pnh_.advertiseService("reset_pose",
01258     &InteractiveMarkerInterface::reset_cb, this);
01259   */
01260   if (mode_ == "") {
01261     if (registration_) {
01262       mode_ = "registration";
01263     }
01264     else if (robot_mode_) {
01265       mode_ = "robot";
01266     }
01267     else {
01268       mode_ = "model";
01269     }
01270   }
01271   serv_lock_joint_states_ = pnh_.advertiseService("lock_joint_states",
01272                                                   &UrdfModelMarker::lockJointStates,
01273                                                   this);
01274   serv_unlock_joint_states_ = pnh_.advertiseService("unlock_joint_states",
01275                                                     &UrdfModelMarker::unlockJointStates,
01276                                                     this);
01277 
01278   if (mode_ == "registration") {
01279     model_menu_.insert("Registration",
01280                         boost::bind(&UrdfModelMarker::registrationCB, this, _1));
01281   }
01282   else if (mode_ == "visualization") {
01283 
01284   }
01285   else if (mode_ == "robot") {
01286     interactive_markers::MenuHandler::EntryHandle sub_menu_move_;
01287     sub_menu_move_ = model_menu_.insert("Move");
01288     model_menu_.insert(sub_menu_move_, "Joint",
01289                         boost::bind(&UrdfModelMarker::jointMoveCB, this, _1));
01290     model_menu_.insert(sub_menu_move_, "Base",
01291                         boost::bind(&UrdfModelMarker::publishMarkerMenu, this, _1, jsk_interactive_marker::MarkerMenu::MOVE));
01292 
01293     interactive_markers::MenuHandler::EntryHandle sub_menu_reset_;
01294     sub_menu_reset_ = model_menu_.insert("Reset Marker Pose");
01295     model_menu_.insert(sub_menu_reset_, "Joint",
01296                         boost::bind(&UrdfModelMarker::resetMarkerCB, this, _1));
01297     model_menu_.insert(sub_menu_reset_, "Base",
01298                         boost::bind(&UrdfModelMarker::resetBaseMarkerCB, this, _1));
01299 
01300 
01301     interactive_markers::MenuHandler::EntryHandle sub_menu_pose_;
01302     sub_menu_pose_ = model_menu_.insert("Special Pose");
01303 
01304     model_menu_.insert(sub_menu_pose_, "Stand Pose",
01305                         boost::bind(&UrdfModelMarker::publishMarkerMenu, this, _1, 100));
01306 
01307     model_menu_.insert(sub_menu_pose_, "Manip Pose",
01308                         boost::bind(&UrdfModelMarker::publishMarkerMenu, this, _1, 101));
01309 
01310     //model_menu_.insert("Reset Marker Pose",
01311     //boost::bind(&UrdfModelMarker::resetMarkerCB, this, _1));
01312 
01313 
01314     model_menu_.insert("Hide Marker" ,
01315                         boost::bind(&UrdfModelMarker::hideMarkerCB, this, _1));
01316     model_menu_.insert("Hide All Marker" ,
01317                         boost::bind(&UrdfModelMarker::hideAllMarkerCB, this, _1));
01318 
01319 
01320   }
01321   else if (mode_ == "model") {
01322     model_menu_.insert("Grasp Point",
01323                         boost::bind(&UrdfModelMarker::graspPointCB, this, _1));
01324     model_menu_.insert("Move",
01325                         boost::bind(&UrdfModelMarker::moveCB, this, _1));
01326     model_menu_.insert("Set as present pose",
01327                         boost::bind(&UrdfModelMarker::setPoseCB, this, _1));
01328     model_menu_.insert("Hide Marker" ,
01329                         boost::bind(&UrdfModelMarker::hideMarkerCB, this, _1));
01330     model_menu_.insert("Hide All Marker" ,
01331                         boost::bind(&UrdfModelMarker::hideAllMarkerCB, this, _1));
01332   }
01333 
01334   // get the entire file
01335   std::string xml_string;
01336 
01337   if (use_robot_description_) {
01338     ROS_INFO("loading robot_description from parameter %s", model_file_.c_str());
01339     nh_.getParam(model_file_, xml_string);
01340 
01341   }
01342   else {
01343     ROS_INFO_STREAM("loading model_file: " << model_file_);
01344     model_file_ = getFilePathFromRosPath(model_file_);
01345     model_file_ = getFullPathFromModelPath(model_file_);
01346     try {
01347       if (!boost::filesystem::exists(model_file_.c_str())) {
01348         ROS_ERROR("%s does not exists", model_file_.c_str());
01349       }
01350       else {
01351         std::fstream xml_file(model_file_.c_str(), std::fstream::in);
01352         while (xml_file.good())
01353         {
01354           std::string line;
01355           std::getline(xml_file, line);
01356           xml_string += (line + "\n");
01357         }
01358         xml_file.close();
01359         ROS_INFO_STREAM("finish loading model_file: " << model_file_);
01360       }
01361     }
01362     catch (...) {
01363       ROS_ERROR("model or mesh not found: %s", model_file_.c_str());
01364       ROS_ERROR("Please check GAZEBO_MODEL_PATH");
01365     }
01366   }
01367   ROS_INFO("xml_string is %lu size", xml_string.length());
01368   model = parseURDF(xml_string);
01369 
01370   if (!model) {
01371     ROS_ERROR("ERROR: Model Parsing the xml failed");
01372     return;
01373   }
01374   else {
01375     ROS_INFO("model name is %s", model->getName().c_str());
01376   }
01377   if (mode_ == "robot") {
01378     resetRobotBase();
01379   }
01380   addChildLinkNames(model->getRoot(), true, true);
01381 
01382   publishJointState();
01383   setPoseCB(); //init joint_state_origin
01384 
01385   resetRootForVisualization();
01386   geometry_msgs::Pose pose;
01387   pose.orientation.w = 1.0;
01388   //callSetDynamicTf(parent_frame_id, frame_id, Pose2Transform(pose));
01389   return;
01390 }
01391 
01392 bool UrdfModelMarker::lockJointStates(std_srvs::EmptyRequest& req,
01393                                       std_srvs::EmptyRequest& res)
01394 {
01395   boost::mutex::scoped_lock lock(joint_states_mutex_);
01396   is_joint_states_locked_ = true;
01397   return true;
01398 }
01399 
01400 bool UrdfModelMarker::unlockJointStates(std_srvs::EmptyRequest& req,
01401                                         std_srvs::EmptyRequest& res)
01402 {
01403   boost::mutex::scoped_lock lock(joint_states_mutex_);
01404   is_joint_states_locked_ = false;
01405   return true;
01406 }
01407 
01408 
01409 void UrdfModelMarker::updateDiagnostic(
01410   diagnostic_updater::DiagnosticStatusWrapper &stat)
01411 {
01412   boost::mutex::scoped_lock(mutex_);
01413   stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "UrdfModelMarker running");
01414   stat.add("Time to set dynamic tf (Avg.)",
01415            dynamic_tf_check_time_acc_.mean());
01416   stat.add("Time to set dynamic tf (Max)",
01417            dynamic_tf_check_time_acc_.max());
01418   stat.add("Time to set dynamic tf (Min)",
01419            dynamic_tf_check_time_acc_.min());
01420   stat.add("Time to set dynamic tf (Var.)",
01421            dynamic_tf_check_time_acc_.variance());
01422 
01423   stat.add("Time to set joint states (Avg.)",
01424            reset_joint_states_check_time_acc_.mean());
01425   stat.add("Time to set joint states (Max)",
01426            reset_joint_states_check_time_acc_.max());
01427   stat.add("Time to set joint states (Min)",
01428            reset_joint_states_check_time_acc_.min());
01429   stat.add("Time to set joint states (Var.)",
01430            reset_joint_states_check_time_acc_.variance());
01431 
01432 }


jsk_interactive_marker
Author(s): furuta
autogenerated on Wed May 1 2019 02:40:31