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


jsk_interactive_marker
Author(s): furuta
autogenerated on Sun Sep 13 2015 22:29:27