1 #include "urdf_parser/urdf_parser.h"     7 #include <dynamic_tf_publisher/SetDynamicTF.h>     8 #include <Eigen/Geometry>    10 #include <kdl/frames_io.hpp>    13 #include <boost/filesystem.hpp>    20   visualization_msgs::InteractiveMarkerControl control;
    23     for(
int i=0; i<int_marker.controls.size(); i++) {
    24       int_marker.controls[i].always_visible = 
true;
    29     Eigen::Vector3f origin_x(1,0,0);
    30     Eigen::Vector3f dest_x(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z);
    31     Eigen::Quaternionf qua;
    33     qua.setFromTwoVectors(origin_x, dest_x);
    34     control.orientation.x = qua.x();
    35     control.orientation.y = qua.y();
    36     control.orientation.z = qua.z();
    37     control.orientation.w = qua.w();
    39     int_marker.scale = 0.5;
    41     switch(parent_joint->type) {
    43     case Joint::CONTINUOUS:
    44       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
    45       int_marker.controls.push_back(control);
    47     case Joint::PRISMATIC:
    48       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
    49       int_marker.controls.push_back(control);
    58   visualization_msgs::InteractiveMarkerControl control;
    60   visualization_msgs::Marker 
marker;
    63   marker.type = visualization_msgs::Marker::CYLINDER;
    65   marker.scale.x = scale;
    66   marker.scale.y = scale * 1;
    67   marker.scale.z = scale * 40;
    72   Eigen::Vector3f origin_x(0,0,1);
    73   Eigen::Vector3f dest_x(parent_joint->axis.x, parent_joint->axis.y, parent_joint->axis.z);
    74   Eigen::Quaternionf qua;
    76   qua.setFromTwoVectors(origin_x, dest_x);
    77   marker.pose.orientation.x = qua.x();
    78   marker.pose.orientation.y = qua.y();
    79   marker.pose.orientation.z = qua.z();
    80   marker.pose.orientation.w = qua.w();
    82   control.markers.push_back(marker);
    83   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
    84   control.always_visible = 
true;
    86   int_marker.controls.push_back(control);
    93   visualization_msgs::InteractiveMarkerControl control;
    94   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
    95   visualization_msgs::Marker 
marker;
    96   marker.type = visualization_msgs::Marker::SPHERE;
    97   marker.scale.x = 0.05;
    98   marker.scale.y = 0.05;
    99   marker.scale.z = 0.05;
   101   marker.color.a = 1.0;
   102   marker.color.r = 1.0;
   103   marker.color.g = 1.0;
   104   marker.color.b = 0.0;
   106   control.markers.push_back(marker);
   107   control.always_visible = 
true;
   108   int_marker.controls.push_back(control);
   110   if (linkMarkerMap[link_frame_name_].gp.displayMoveMarker) {
   118   dynamic_tf_publisher::SetDynamicTF SetTf;
   120   SetTf.request.freq = 20;
   123   SetTf.request.cur_tf.header.frame_id = parent_frame_id;
   124   SetTf.request.cur_tf.child_frame_id = 
frame_id;
   125   SetTf.request.cur_tf.transform = transform;
   126   if (use_dynamic_tf_ || parent_frame_id == frame_id_) {
   133   if (use_dynamic_tf_) {
   135     dynamic_tf_publisher_publish_tf_client.call(req);
   140   publishBasePose(feedback->pose, feedback->header);
   144   geometry_msgs::PoseStamped ps;
   147   pub_base_pose_.publish(ps);
   153   publishMarkerPose(feedback->pose, feedback->header, feedback->marker_name);
   157   jsk_interactive_marker::MarkerPose mp;
   158   mp.pose.header = header;
   160   mp.marker_name = marker_name;
   161   mp.type = jsk_interactive_marker::MarkerPose::GENERAL;
   167   jsk_interactive_marker::MarkerMenu m;
   168   m.marker_name = feedback->marker_name;
   170   pub_move_.publish(m);
   176   jsk_interactive_marker::MarkerMenu m;
   194   pub_joint_state_.publish(js);
   202     init_stamp_ = ps.header.stamp;
   203     tfl_.transformPose(frame_id_, ps, ps);
   205     geometry_msgs::Pose 
pose = getRootPose(ps.pose);
   207     string root_frame = tf_prefix_ + model->getRoot()->name;
   208     linkMarkerMap[frame_id_].pose = pose;
   211     addChildLinkNames(model->getRoot(), 
true, 
false);
   212     publishMarkerPose(pose, ps.header, root_frame);
   225   boost::mutex::scoped_lock 
lock(joint_states_mutex_);
   226   if (is_joint_states_locked_) {
   230   setJointState(model->getRoot(), msg);
   231   republishJointState(*msg);
   239   resetRootForVisualization();
   240   server_->applyChanges();
   246   switch (feedback->event_type) {
   247   case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
   248   case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
   249     linkMarkerMap[
frame_id].pose = feedback->pose;
   251     if (parent_frame_id == frame_id_) {
   252       root_pose_ = feedback->pose;
   253       publishBasePose(feedback);
   255     callSetDynamicTf(parent_frame_id, frame_id, 
Pose2Transform(feedback->pose));
   256     publishMarkerPose(feedback);
   257     publishJointState(feedback);
   259   case visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK:
   260     cout << 
"clicked" << 
" frame:" << frame_id << mode_ << endl;
   262     if (mode_ != 
"visualization") {
   263       linkMarkerMap[linkMarkerMap[
frame_id].movable_link].displayMoveMarker ^= 
true;
   264       addChildLinkNames(model->getRoot(), 
true, 
false);
   267       geometry_msgs::PoseStamped ps = getOriginPoseStamped();
   268       pub_selected_.publish(ps);
   269       jsk_recognition_msgs::Int32Stamped index_msg;
   270       index_msg.data = index_;
   271       index_msg.header.stamp = init_stamp_;
   272       pub_selected_index_.publish(index_msg);
   277   diagnostic_updater_->update();
   287   KDL::Vector graspVec(feedback->mouse_point.x, feedback->mouse_point.y, feedback->mouse_point.z);
   291   graspVec = parentFrame.
Inverse(graspVec);
   293   geometry_msgs::Pose 
p;
   294   p.position.x = graspVec.
x();
   295   p.position.y = graspVec.
y();
   296   p.position.z = graspVec.
z();
   297   p.orientation = linkMarkerMap[feedback->marker_name].gp.pose.orientation;
   298   linkMarkerMap[feedback->marker_name].gp.pose = p;
   300   linkMarkerMap[feedback->marker_name].gp.displayGraspPoint = 
true;
   301   addChildLinkNames(model->getRoot(), 
true, 
false);
   307   publishJointState(feedback);
   309   publishMarkerMenu(feedback, jsk_interactive_marker::MarkerMenu::JOINT_MOVE);
   314   publishJointState(feedback);
   315   publishMarkerMenu(feedback, jsk_interactive_marker::MarkerMenu::RESET_JOINT);
   328   geometry_msgs::PoseStamped ps;
   329   ps.header.frame_id = frame_id_;
   330   ps.pose = root_pose_;
   334   addChildLinkNames(model->getRoot(), 
true, 
false);
   341     geometry_msgs::TransformStamped ts_msg;
   342     tfl_.lookupTransform(frame_id_, model->getRoot()->name,
   354   if (fixed_link_.size() > 0 && (mode_ == 
"visualization" || mode_ == 
"robot")) {
   355     string marker_name =  tf_prefix_ + model->getRoot()->name;
   357     bool first_offset = 
true;
   358     for(
int i=0; i<fixed_link_.size(); i++) {
   359       std::string link = fixed_link_[i];
   361         ROS_DEBUG_STREAM(
"fixed_link:" << tf_prefix_ + model->getRoot()->name << tf_prefix_ + link);
   362         const std::string source_frame = tf_prefix_ + link;
   363         const std::string 
target_frame = tf_prefix_ + model->getRoot()->name;
   367           tfl_.waitForTransform(target_frame, source_frame, now, 
ros::Duration(5.0));
   368           tfl_.lookupTransform(target_frame, source_frame,
   369                                now, st_link_offset);
   374             first_offset = 
false;
   382           ROS_ERROR(
"Failed to lookup transformation from %s to %s: %s",
   383                         source_frame.c_str(), target_frame.c_str(),
   391     geometry_msgs::TransformStamped ts_fixed_link_offset;
   392     ts_fixed_link_offset.transform.translation.x = fixed_link_offset_.position.x;
   393     ts_fixed_link_offset.transform.translation.y = fixed_link_offset_.position.y;
   394     ts_fixed_link_offset.transform.translation.z = fixed_link_offset_.position.z;
   395     ts_fixed_link_offset.transform.rotation = fixed_link_offset_.orientation;
   400     transform = st_offset * st_fixed_link_offset;
   403     geometry_msgs::Transform tf_msg;
   406     root_offset_.position.x = tf_msg.translation.x;
   407     root_offset_.position.y = tf_msg.translation.y;
   408     root_offset_.position.z = tf_msg.translation.z;
   409     root_offset_.orientation = tf_msg.rotation;
   412     geometry_msgs::PoseStamped ps;
   414     ps.header.frame_id = frame_id_;
   415     ps.pose.orientation.w = 1.0;
   417     root_pose_ = ps.pose;
   419     geometry_msgs::Pose 
pose = getRootPose(ps.pose);
   421     string root_frame = tf_prefix_ + model->getRoot()->name;
   422     linkMarkerMap[frame_id_].pose = pose;
   425     addChildLinkNames(model->getRoot(), 
true, 
false);
   434   publishJointState(feedback);
   439   jsk_interactive_marker::MoveModel mm;
   440   mm.header = feedback->header;
   441   mm.name = model_name_;
   442   mm.description = model_description_;
   443   mm.joint_state_origin = joint_state_origin_;
   444   mm.joint_state_goal = joint_state_;
   445   mm.pose_origin.header.frame_id = frame_id_;
   446   mm.pose_origin.pose = root_pose_origin_;
   447   mm.pose_goal.header.frame_id = frame_id_;
   448   mm.pose_goal.pose = root_pose_;
   449   pub_move_model_.publish(mm);
   453   jsk_interactive_marker::MoveObject mo;
   454   mo.origin.header = feedback->header;
   455   mo.origin.pose = linkMarkerMap[feedback->marker_name].origin;
   457   mo.goal.header = feedback->header;
   458   mo.goal.pose = feedback->pose;
   460   mo.graspPose = linkMarkerMap[feedback->marker_name].gp.pose;
   461   pub_move_object_.publish(mo);
   466   cout << 
"setPose" <<endl;
   467   joint_state_origin_ = joint_state_;
   468   root_pose_origin_ = root_pose_;
   469   setOriginalPose(model->getRoot());
   477   linkMarkerMap[linkMarkerMap[feedback->marker_name].movable_link].displayMoveMarker = 
false;
   478   addChildLinkNames(model->getRoot(), 
true, 
false);
   482   map<string, linkProperty>::iterator it = linkMarkerMap.begin();
   483   while (it != linkMarkerMap.end())
   485     (*it).second.displayMoveMarker = 
false;
   488   addChildLinkNames(model->getRoot(), 
true, 
false);
   492   map<string, linkProperty>::iterator it = linkMarkerMap.begin();
   493   while (it != linkMarkerMap.end())
   495     (*it).second.displayModelMarker = 
false;
   498   addChildLinkNames(model->getRoot(), 
true, 
false);
   502   map<string, linkProperty>::iterator it = linkMarkerMap.begin();
   503   while (it != linkMarkerMap.end())
   505     (*it).second.displayModelMarker = 
true;
   508   addChildLinkNames(model->getRoot(), 
true, 
false);
   515   linkMarkerMap.clear();
   517   model = parseURDF(msg->data);
   519     ROS_ERROR(
"Model Parsing the xml failed");
   522   addChildLinkNames(model->getRoot(), 
true, 
true);
   531   switch (feedback->event_type) {
   532   case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
   533     linkMarkerMap[link_name].gp.pose = feedback->pose;
   534     publishMarkerPose(feedback);
   536   case visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK:
   537     cout << 
"clicked" << 
" frame:" << feedback->marker_name << endl;
   538     linkMarkerMap[link_name].gp.displayMoveMarker ^= 
true;
   539     addChildLinkNames(model->getRoot(), 
true, 
false);
   544 visualization_msgs::InteractiveMarkerControl 
UrdfModelMarker::makeMeshMarkerControl(
const std::string &mesh_resource, 
const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, 
const std_msgs::ColorRGBA &color, 
bool use_color) {
   545   visualization_msgs::Marker meshMarker;
   547   if (use_color) meshMarker.color = color;
   548   meshMarker.mesh_resource = mesh_resource;
   549   meshMarker.mesh_use_embedded_materials = !use_color;
   550   meshMarker.type = visualization_msgs::Marker::MESH_RESOURCE;
   552   meshMarker.scale = scale;
   553   meshMarker.pose = stamped.pose;
   554   visualization_msgs::InteractiveMarkerControl control;
   555   control.markers.push_back(meshMarker);
   556   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
   557   control.always_visible = 
true;
   564   std_msgs::ColorRGBA color;
   575                                                                                     const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, 
const std_msgs::ColorRGBA &color)
   581   visualization_msgs::Marker cylinderMarker;
   583   if (use_color) cylinderMarker.color = color;
   584   cylinderMarker.type = visualization_msgs::Marker::CYLINDER;
   585   cylinderMarker.scale.x = radius * 2;
   586   cylinderMarker.scale.y = radius * 2;
   587   cylinderMarker.scale.z = length;
   588   cylinderMarker.pose = stamped.pose;
   590   visualization_msgs::InteractiveMarkerControl control;
   591   control.markers.push_back(cylinderMarker);
   592   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
   593   control.always_visible = 
true;
   599   visualization_msgs::Marker boxMarker;
   601   fprintf(stderr, 
"urdfModelMarker = %f %f %f\n", dim.x, dim.y, dim.z);
   602   if (use_color) boxMarker.color = color;
   603   boxMarker.type = visualization_msgs::Marker::CUBE;
   604   boxMarker.scale.x = dim.x;
   605   boxMarker.scale.y = dim.y;
   606   boxMarker.scale.z = dim.z;
   607   boxMarker.pose = stamped.pose;
   609   visualization_msgs::InteractiveMarkerControl control;
   610   control.markers.push_back(boxMarker);
   611   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
   612   control.always_visible = 
true;
   618   visualization_msgs::Marker sphereMarker;
   620   if (use_color) sphereMarker.color = color;
   621   sphereMarker.type = visualization_msgs::Marker::SPHERE;
   622   sphereMarker.scale.x = rad * 2;
   623   sphereMarker.scale.y = rad * 2;
   624   sphereMarker.scale.z = rad * 2;
   625   sphereMarker.pose = stamped.pose;
   627   visualization_msgs::InteractiveMarkerControl control;
   628   control.markers.push_back(sphereMarker);
   629   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
   630   control.always_visible = 
true;
   637   pub_joint_state_.publish(joint_state_);
   641   sensor_msgs::JointState new_joint_state;
   642   joint_state_ = new_joint_state;
   644   getJointState(model->getRoot());
   649   string link_frame_name_ =  tf_prefix_ + link->name;
   651   if (parent_joint != 
NULL) {
   658     double jointAngleAllRange;
   659     switch(parent_joint->type) {
   660     case Joint::REVOLUTE:
   661     case Joint::CONTINUOUS:
   663       linkProperty *link_property = &linkMarkerMap[link_frame_name_];
   666       rot = initialFrame.
M.
Inverse() * presentFrame.
M;
   671       if (
KDL::dot(rotVec,jointVec) < 0) {
   672         jointAngle = - jointAngle;
   683       if (parent_joint->type == Joint::REVOLUTE && parent_joint->limits != 
NULL) {
   684         bool changeMarkerAngle = 
false;
   685         if (jointAngleAllRange < parent_joint->limits->lower) {
   686           jointAngleAllRange = parent_joint->limits->lower + 0.001;
   687           changeMarkerAngle = 
true;
   689         if (jointAngleAllRange > parent_joint->limits->upper) {
   690           jointAngleAllRange = parent_joint->limits->upper - 0.001;
   691           changeMarkerAngle = 
true;
   694         if (changeMarkerAngle) {
   695           setJointAngle(link, jointAngleAllRange);
   699       joint_state_.position.push_back(jointAngleAllRange);
   700       joint_state_.name.push_back(parent_joint->name);
   703     case Joint::PRISMATIC:
   706       linkProperty *link_property = &linkMarkerMap[link_frame_name_];
   710       pos = presentFrame.
p - initialFrame.
p;
   715       jointVec = jointVec / jointVec.
Norm(); 
   716       jointAngle = 
KDL::dot(jointVec, pos);
   719       jointAngleAllRange = jointAngle;
   721       if (parent_joint->type == Joint::PRISMATIC && parent_joint->limits != 
NULL) {
   722         bool changeMarkerAngle = 
false;
   723         if (jointAngleAllRange < parent_joint->limits->lower) {
   724           jointAngleAllRange = parent_joint->limits->lower + 0.003;
   725           changeMarkerAngle = 
true;
   727         if (jointAngleAllRange > parent_joint->limits->upper) {
   728           jointAngleAllRange = parent_joint->limits->upper - 0.003;
   729           changeMarkerAngle = 
true;
   731         if (changeMarkerAngle) {
   732           setJointAngle(link, jointAngleAllRange);
   736       joint_state_.position.push_back(jointAngleAllRange);
   737       joint_state_.name.push_back(parent_joint->name);
   745     server_->applyChanges();
   748   for (std::vector<LinkSharedPtr >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) {
   749     getJointState(*child);
   755   string link_frame_name_ =  tf_prefix_ + link->name;
   758   if (parent_joint == 
NULL) {
   768   std_msgs::Header link_header;
   770   int rotation_count = 0;
   772   switch(parent_joint->type) {
   773   case Joint::REVOLUTE:
   774   case Joint::CONTINUOUS:
   776     if (joint_angle > 
M_PI) {
   777       rotation_count = (int)((joint_angle + 
M_PI) / (
M_PI * 2));
   778       joint_angle -= rotation_count * 
M_PI * 2;
   780     else if (joint_angle < -
M_PI) {
   781       rotation_count = (int)((- joint_angle + 
M_PI) / (
M_PI * 2));
   782       joint_angle -= rotation_count * 
M_PI * 2;
   784     linkProperty *link_property = &linkMarkerMap[link_frame_name_];
   799   case Joint::PRISMATIC:
   801     linkProperty *link_property = &linkMarkerMap[link_frame_name_];
   809     jointVec = jointVec / jointVec.
Norm(); 
   810     presentFrame.
p = joint_angle * jointVec + initialFrame.
p;
   819   link_header.frame_id = linkMarkerMap[link_frame_name_].frame_id;
   821   server_->setPose(link_frame_name_, linkMarkerMap[link_frame_name_].
pose, link_header);
   823   callSetDynamicTf(linkMarkerMap[link_frame_name_].
frame_id, link_frame_name_, 
Pose2Transform(linkMarkerMap[link_frame_name_].pose));
   828   string link_frame_name_ =  tf_prefix_ + link->name;
   830   if (parent_joint != 
NULL) {
   837     bool changeAngle = 
false;
   838     std_msgs::Header link_header;
   839     switch(parent_joint->type) {
   840     case Joint::REVOLUTE:
   841     case Joint::CONTINUOUS:
   842       for(
int i=0; i< js->name.size(); i++) {
   843         if (js->name[i] == parent_joint->name) {
   844           jointAngle = js->position[i];
   852       setJointAngle(link, jointAngle);
   854     case Joint::PRISMATIC:
   855       for(
int i=0; i< js->name.size(); i++) {
   856         if (js->name[i] == parent_joint->name) {
   857           jointAngle = js->position[i];
   865       setJointAngle(link, jointAngle);
   871   for (std::vector<LinkSharedPtr >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) {
   872     setJointState(*child, js);
   881   pose_frame = pose_frame * offset_frame.
Inverse();
   887   geometry_msgs::PoseStamped ps;
   888   geometry_msgs::Pose 
pose;
   893   pose_frame = pose_frame * offset_frame;
   896   ps.header.frame_id = frame_id_;
   897   ps.header.stamp = init_stamp_;
   904   string link_frame_name_ =  tf_prefix_ + link->name;
   905   linkMarkerMap[link_frame_name_].origin =  linkMarkerMap[link_frame_name_].pose;
   907   for (std::vector<LinkSharedPtr >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) {
   908     setOriginalPose(*child);
   914   addChildLinkNames(link, root, init, use_visible_color_, 0);
   919   geometry_msgs::PoseStamped ps;
   921   double scale_factor = 1.02;
   922   string link_frame_name_ =  tf_prefix_ + link->name;
   923   string parent_link_frame_name_;
   924   ROS_INFO(
"link_frame_name: %s", link_frame_name_.c_str());
   926     parent_link_frame_name_ = frame_id_;
   928     ps.pose = getRootPose(root_pose_);
   931     parent_link_frame_name_ = link->parent_joint->parent_link_name;
   932     parent_link_frame_name_ = tf_prefix_ + parent_link_frame_name_;
   933     ps.pose = 
UrdfPose2Pose(link->parent_joint->parent_to_joint_origin_transform);
   935   ps.header.frame_id =  parent_link_frame_name_;
   940     callSetDynamicTf(parent_link_frame_name_, link_frame_name_, 
Pose2Transform(ps.pose));
   945     if (link->parent_joint !=
NULL) {
   950     if (link->parent_joint !=
NULL && link->parent_joint->type == Joint::FIXED) {
   951       lp.
movable_link = linkMarkerMap[parent_link_frame_name_].movable_link;
   957     linkMarkerMap.insert(map<string, linkProperty>::value_type(link_frame_name_, lp));
   960   linkMarkerMap[link_frame_name_].frame_id = parent_link_frame_name_;
   962   visualization_msgs::InteractiveMarker int_marker;
   963   int_marker.header = ps.header;
   965   int_marker.name = link_frame_name_;
   967     int_marker.description = model_description_;
   969   int_marker.scale = 1.0;
   970   int_marker.pose = ps.pose;
   973   if (!init && !root) {
   974     visualization_msgs::InteractiveMarker old_marker;
   975     if (server_->get(link_frame_name_, old_marker)) {
   976       int_marker.pose = old_marker.pose;
   982   if (!linkMarkerMap[link_frame_name_].displayModelMarker) {
   983     server_->erase(link_frame_name_);
   984     server_->erase(tf_prefix_ + link->name + 
"/grasp"); 
   989     if (linkMarkerMap[link_frame_name_].displayMoveMarker) {
   990       addMoveMarkerControl(int_marker, link, root);
   993     std_msgs::ColorRGBA color;
   994     if (mode_ == 
"visualization") {
   995       color.r = (double)0xFF / 0xFF;
   996       color.g = (double)0xFF / 0xFF;
   997       color.b = (double)0x00 / 0xFF;
  1001       switch(color_index %3) {
  1003         color.r = (double)0xFF / 0xFF;
  1004         color.g = (double)0xC3 / 0xFF;
  1005         color.b = (double)0x00 / 0xFF;
  1008         color.r = (double)0x58 / 0xFF;
  1009         color.g = (double)0x0E / 0xFF;
  1010         color.b = (double)0xAD / 0xFF;
  1013         color.r = (double)0x0C / 0xFF;
  1014         color.g = (double)0x5A / 0xFF;
  1015         color.b = (double)0xA6 / 0xFF;
  1022     std::vector<VisualSharedPtr > visual_array;
  1023     if (link->visual_array.size() != 0) {
  1024       visual_array = link->visual_array;
  1026     else if (link->visual.get() != 
NULL) {
  1027       visual_array.push_back(link->visual);
  1029     for(
int i=0; i<visual_array.size(); i++) {
  1031       if (link_visual.get() != 
NULL && link_visual->geometry.get() != 
NULL) {
  1032         visualization_msgs::InteractiveMarkerControl meshControl;
  1033         if (link_visual->geometry->type == Geometry::MESH) {
  1034 #if ROS_VERSION_MINIMUM(1,14,0) // melodic  1035           MeshConstSharedPtr mesh = std::static_pointer_cast<
const Mesh>(link_visual->geometry);
  1037           MeshConstSharedPtr mesh = boost::static_pointer_cast<
const Mesh>(link_visual->geometry);
  1039           string model_mesh_ = mesh->filename;
  1040           if (linkMarkerMap[link_frame_name_].
mesh_file == 
"") {
  1042             linkMarkerMap[link_frame_name_].mesh_file = model_mesh_;
  1045             model_mesh_ = linkMarkerMap[link_frame_name_].mesh_file;
  1049           geometry_msgs::Vector3 mesh_scale;
  1050           mesh_scale.x = mesh->scale.x;
  1051           mesh_scale.y = mesh->scale.y;
  1052           mesh_scale.z = mesh->scale.z;
  1053           ROS_INFO(
"make mesh marker from %s", model_mesh_.c_str());
  1061         else if (link_visual->geometry->type == Geometry::CYLINDER) {
  1062 #if ROS_VERSION_MINIMUM(1,14,0) // melodic  1068           double length = cylinder->length;
  1069           double radius = cylinder->radius;
  1070           ROS_INFO_STREAM(
"cylinder " << link->name << 
", length =  " << length << 
", radius " << radius);
  1078         else if (link_visual->geometry->type == Geometry::BOX) {
  1079 #if ROS_VERSION_MINIMUM(1,14,0) // melodic  1080           BoxConstSharedPtr box = std::static_pointer_cast<
const Box>(link_visual->geometry);
  1082           BoxConstSharedPtr box = boost::static_pointer_cast<
const Box>(link_visual->geometry);
  1085           Vector3 dim = box->dim;
  1086           ROS_INFO_STREAM(
"box " << link->name << 
", dim =  " << dim.x << 
", " << dim.y << 
", " << dim.z);
  1094         else if (link_visual->geometry->type == Geometry::SPHERE) {
  1095 #if ROS_VERSION_MINIMUM(1,14,0) // melodic  1101           double rad = sphere->radius;
  1109         int_marker.controls.push_back(meshControl);
  1111         server_->insert(int_marker);
  1112         server_->setCallback(int_marker.name,
  1115         model_menu_.apply(*server_, link_frame_name_);
  1120         if (parent_joint != 
NULL) {
  1121           if (parent_joint->type==Joint::REVOLUTE || parent_joint->type==Joint::REVOLUTE) {
  1122             addInvisibleMeshMarkerControl(int_marker, link, color);
  1123             server_->insert(int_marker);
  1124             server_->setCallback(int_marker.name,
  1126             model_menu_.apply(*server_, link_frame_name_);
  1133       if (linkMarkerMap[link_frame_name_].gp.displayGraspPoint) {
  1134         visualization_msgs::InteractiveMarker grasp_int_marker;
  1135         double grasp_scale_factor = 1.02;
  1136         string grasp_link_frame_name_ = tf_prefix_ + link->name + 
"/grasp";
  1137         string grasp_parent_link_frame_name_ = tf_prefix_ + link->name;
  1139         geometry_msgs::PoseStamped grasp_ps;
  1140         grasp_ps.pose = linkMarkerMap[link_frame_name_].gp.pose;
  1141         grasp_ps.header.frame_id =  grasp_parent_link_frame_name_;
  1143         grasp_int_marker.header = grasp_ps.header;
  1144         grasp_int_marker.name = grasp_link_frame_name_;
  1145         grasp_int_marker.scale = grasp_scale_factor;
  1146         grasp_int_marker.pose = grasp_ps.pose;
  1148         addGraspPointControl(grasp_int_marker, link_frame_name_);
  1150         server_->insert(grasp_int_marker);
  1151         server_->setCallback(grasp_int_marker.name,
  1160     if (!root && initial_pose_map_.count(link->parent_joint->name) != 0) {
  1161       setJointAngle(link, initial_pose_map_[link->parent_joint->name]);
  1167   for (std::vector<LinkSharedPtr >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) {
  1168     addChildLinkNames(*child, 
false, init, use_color, color_index + 1);
  1171     server_->applyChanges();
  1180 UrdfModelMarker::UrdfModelMarker (
string model_name, 
string model_description, 
string model_file, 
string frame_id, geometry_msgs::PoseStamped root_pose, geometry_msgs::Pose root_offset, 
double scale_factor, 
string mode, 
bool robot_mode, 
bool registration, 
vector<string> fixed_link, 
bool use_robot_description, 
bool use_visible_color, map<string, double> initial_pose_map, 
int index,  std::shared_ptr<interactive_markers::InteractiveMarkerServer> 
server) : nh_(), pnh_(
"~"), tfl_(nh_),use_dynamic_tf_(true), is_joint_states_locked_(false) {
  1202     ss << model_name << index;
  1262       mode_ = 
"registration";
  1278   if (
mode_ == 
"registration") {
  1282   else if (
mode_ == 
"visualization") {
  1285   else if (
mode_ == 
"robot") {
  1321   else if (
mode_ == 
"model") {
  1343     ROS_INFO_STREAM(
"loading model_file: " << 
model_file_);
  1347       if (!boost::filesystem::exists(
model_file_.c_str())) {
  1351         std::fstream xml_file(
model_file_.c_str(), std::fstream::in);
  1352         while (xml_file.good())
  1355           std::getline(xml_file, line);
  1356           xml_string += (line + 
"\n");
  1359         ROS_INFO_STREAM(
"finish loading model_file: " << 
model_file_);
  1364       ROS_ERROR(
"Please check GAZEBO_MODEL_PATH");
  1367   ROS_INFO(
"xml_string is %lu size", xml_string.length());
  1368   model = parseURDF(xml_string);
  1371     ROS_ERROR(
"ERROR: Model Parsing the xml failed");
  1375     ROS_INFO(
"model name is %s", model->getName().c_str());
  1377   if (
mode_ == 
"robot") {
  1386   geometry_msgs::Pose 
pose;
  1387   pose.orientation.w = 1.0;
  1393                                       std_srvs::EmptyRequest& res)
  1401                                         std_srvs::EmptyRequest& res)
  1412   stat.
summary(diagnostic_msgs::DiagnosticStatus::OK, 
"UrdfModelMarker running");
  1413   stat.
add(
"Time to set dynamic tf (Avg.)",
  1415   stat.
add(
"Time to set dynamic tf (Max)",
  1417   stat.
add(
"Time to set dynamic tf (Min)",
  1419   stat.
add(
"Time to set dynamic tf (Var.)",
  1422   stat.
add(
"Time to set joint states (Avg.)",
  1424   stat.
add(
"Time to set joint states (Max)",
  1426   stat.
add(
"Time to set joint states (Min)",
  1428   stat.
add(
"Time to set joint states (Var.)",
 void addInvisibleMeshMarkerControl(visualization_msgs::InteractiveMarker &int_marker, LinkConstSharedPtr link, const std_msgs::ColorRGBA &color)
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
visualization_msgs::InteractiveMarkerControl makeBoxMarkerControl(const geometry_msgs::PoseStamped &stamped, Vector3 dim, const std_msgs::ColorRGBA &color, bool use_color)
void addMoveMarkerControl(visualization_msgs::InteractiveMarker &int_marker, LinkConstSharedPtr link, bool root)
ros::Publisher pub_base_pose_
ros::Subscriber sub_reset_joints_
void graspPointCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
boost::mutex joint_states_mutex_
void hideAllMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
visualization_msgs::InteractiveMarkerControl makeBoxMarkerControl(const geometry_msgs::PoseStamped &stamped, Vector3 dim, const std_msgs::ColorRGBA &color, bool use_color)
geometry_msgs::Pose root_pose_
void republishJointState(sensor_msgs::JointState js)
void addGraspPointControl(visualization_msgs::InteractiveMarker &int_marker, std::string link_frame_name_)
void summary(unsigned char lvl, const std::string s)
void showModelMarkerCB(const std_msgs::EmptyConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber show_marker_
ros::Publisher pub_move_model_
std::string getFullPathFromModelPath(std::string path)
ros::Subscriber sub_set_root_pose_
void addChildLinkNames(LinkConstSharedPtr link, bool root, bool init)
geometry_msgs::Transform Pose2Transform(const geometry_msgs::Pose pose_msg)
bool call(MReq &req, MRes &res)
geometry_msgs::PoseStamped getOriginPoseStamped()
geometry_msgs::Pose origin
ROSCPP_DECL const std::string & getName()
void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
void resetJointStatesCB(const sensor_msgs::JointStateConstPtr &msg, bool update_root)
ros::Subscriber sub_reset_joints_and_root_
geometry_msgs::Pose initial_pose
void callSetDynamicTf(string parent_frame_id, string frame_id, geometry_msgs::Transform transform)
ros::Publisher pub_move_object_
visualization_msgs::InteractiveMarkerControl makeSphereMarkerControl(const geometry_msgs::PoseStamped &stamped, double rad, const std_msgs::ColorRGBA &color, bool use_color)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void resetBaseMsgCB(const std_msgs::EmptyConstPtr &msg)
ModelInterfaceSharedPtr model
geometry_msgs::Pose Transform2Pose(const geometry_msgs::Transform tf_msg)
void setUrdfCB(const std_msgs::StringConstPtr &msg)
void setOriginalPose(LinkConstSharedPtr link)
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
visualization_msgs::InteractiveMarkerControl makeMeshMarkerControl(const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color, bool use_color)
ros::ServiceClient dynamic_tf_publisher_client
void publishMarkerPose(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void jointMoveCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
double GetRotAngle(Vector &axis, double eps=epsilon) const
bool is_joint_states_locked_
void graspPoint_feedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, string link_name)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::string getRosPathFromModelPath(std::string path)
jsk_topic_tools::TimeAccumulator reset_joint_states_check_time_acc_
void setJointAngle(LinkConstSharedPtr link, double joint_angle)
void resetMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
bool getParam(const std::string &key, std::string &s) const
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
Quaternion slerp(const Quaternion &q, const tfScalar &t) const
std::string model_description_
visualization_msgs::InteractiveMarkerControl makeCylinderMarkerControl(const geometry_msgs::PoseStamped &stamped, double length, double radius, const std_msgs::ColorRGBA &color, bool use_color)
void setRootPose(geometry_msgs::PoseStamped ps)
ros::ServiceServer serv_unlock_joint_states_
ros::ServiceClient dynamic_tf_publisher_publish_tf_client
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
map< string, double > initial_pose_map_
def xml_string(rootXml, addHeader=True)
geometry_msgs::Pose getRootPose(geometry_msgs::Pose pose)
#define ROS_DEBUG_STREAM(args)
void proc_feedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, string parent_frame_id, string frame_id)
void publishBasePose(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
ros::Subscriber hide_marker_
void moveCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
bool use_robot_description_
void resetRootForVisualization()
void publishMarkerMenu(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int menu)
std::string getFilePathFromRosPath(std::string rospath)
jsk_topic_tools::TimeAccumulator dynamic_tf_check_time_acc_
EntryHandle insert(const std::string &title, const FeedbackCallback &feedback_cb)
geometry_msgs::Pose root_offset_
ros::ServiceServer serv_lock_joint_states_
#define ROS_INFO_STREAM(args)
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server_
bool unlockJointStates(std_srvs::EmptyRequest &req, std_srvs::EmptyRequest &res)
void registrationCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void add6DofControl(visualization_msgs::InteractiveMarker &msg, bool fixed=false)
interactive_markers::MenuHandler model_menu_
ros::Publisher pub_selected_index_
ros::Subscriber sub_set_urdf_
void publishMoveObject(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
geometry_msgs::Pose fixed_link_offset_
visualization_msgs::InteractiveMarkerControl makeMeshMarkerControl(const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color, bool use_color)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
ros::Publisher pub_joint_state_
std::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
static void transformStampedTFToMsg(const StampedTransform &bt, geometry_msgs::TransformStamped &msg)
void resetBaseMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
static Rotation Rot(const Vector &rotvec, double angle)
vector< string > fixed_link_
void add(const std::string &key, const T &val)
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server
void setRootPoseCB(const geometry_msgs::PoseStampedConstPtr &msg)
visualization_msgs::InteractiveMarkerControl makeSphereMarkerControl(const geometry_msgs::PoseStamped &stamped, double rad, const std_msgs::ColorRGBA &color, bool use_color)
ROSCPP_DECL void spinOnce()
geometry_msgs::Pose UrdfPose2Pose(const urdf::Pose pose)
double Norm(double eps=epsilon) const
static void transformStampedMsgToTF(const geometry_msgs::TransformStamped &msg, StampedTransform &bt)
static void transformTFToMsg(const Transform &bt, geometry_msgs::Transform &msg)
bool lockJointStates(std_srvs::EmptyRequest &req, std_srvs::EmptyRequest &res)
void hideMarkerCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void setJointState(LinkConstSharedPtr link, const sensor_msgs::JointStateConstPtr &js)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
visualization_msgs::InteractiveMarkerControl makeCylinderMarkerControl(const geometry_msgs::PoseStamped &stamped, double length, double radius, const std_msgs::ColorRGBA &color, bool use_color)
void hideModelMarkerCB(const std_msgs::EmptyConstPtr &msg)
ros::Publisher pub_selected_