00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <moveit/robot_interaction/robot_interaction.h>
00039 #include <moveit/robot_interaction/interaction_handler.h>
00040 #include <moveit/robot_interaction/interactive_marker_helpers.h>
00041 #include <moveit/robot_interaction/kinematic_options_map.h>
00042 #include <moveit/transforms/transforms.h>
00043 #include <interactive_markers/interactive_marker_server.h>
00044 #include <interactive_markers/menu_handler.h>
00045 #include <eigen_conversions/eigen_msg.h>
00046 #include <tf_conversions/tf_eigen.h>
00047 #include <boost/lexical_cast.hpp>
00048 #include <boost/math/constants/constants.hpp>
00049 #include <boost/algorithm/string.hpp>
00050
00051 #include <algorithm>
00052 #include <limits>
00053
00054 #include <Eigen/Core>
00055 #include <Eigen/Geometry>
00056
00057 namespace robot_interaction
00058 {
00059
00060 static const float END_EFFECTOR_UNREACHABLE_COLOR[4] = { 1.0, 0.3, 0.3, 1.0 };
00061 static const float END_EFFECTOR_REACHABLE_COLOR[4] = { 0.2, 1.0, 0.2, 1.0 };
00062
00063 const std::string RobotInteraction::INTERACTIVE_MARKER_TOPIC = "robot_interaction_interactive_marker_topic";
00064
00065 RobotInteraction::RobotInteraction(const robot_model::RobotModelConstPtr &robot_model, const std::string &ns)
00066 : robot_model_(robot_model)
00067 , kinematic_options_map_(new KinematicOptionsMap)
00068 {
00069 topic_ = ns.empty() ? INTERACTIVE_MARKER_TOPIC : ns + "/" + INTERACTIVE_MARKER_TOPIC;
00070 int_marker_server_ = new interactive_markers::InteractiveMarkerServer(topic_);
00071
00072
00073 run_processing_thread_ = true;
00074 processing_thread_.reset(new boost::thread(boost::bind(&RobotInteraction::processingThread, this)));
00075 }
00076
00077 RobotInteraction::~RobotInteraction()
00078 {
00079 run_processing_thread_ = false;
00080 new_feedback_condition_.notify_all();
00081 processing_thread_->join();
00082
00083 clear();
00084 delete int_marker_server_;
00085 }
00086
00087 void RobotInteraction::decideActiveComponents(const std::string &group)
00088 {
00089 decideActiveComponents(group, InteractionStyle::SIX_DOF);
00090 }
00091
00092 void RobotInteraction::decideActiveComponents(const std::string &group, InteractionStyle::InteractionStyle style)
00093 {
00094 decideActiveEndEffectors(group, style);
00095 decideActiveJoints(group);
00096 if (active_eef_.empty() && active_vj_.empty() && active_generic_.empty())
00097 ROS_INFO_NAMED("robot_interaction",
00098 "No active joints or end effectors found for group '%s'. "
00099 "Make sure you have defined an end effector in your SRDF file and that "
00100 "kinematics.yaml is loaded in this node's namespace.",
00101 group.c_str());
00102 }
00103
00104 void RobotInteraction::addActiveComponent(const InteractiveMarkerConstructorFn &construct,
00105 const ProcessFeedbackFn &process,
00106 const InteractiveMarkerUpdateFn &update,
00107 const std::string &name)
00108 {
00109 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
00110 GenericInteraction g;
00111 g.construct_marker = construct;
00112 g.update_pose = update;
00113 g.process_feedback = process;
00114
00115 g.marker_name_suffix = "_" + name + "_" + boost::lexical_cast<std::string>(active_generic_.size());
00116 active_generic_.push_back(g);
00117 }
00118
00119 double RobotInteraction::computeGroupMarkerSize(const std::string &group)
00120 {
00121 static const double DEFAULT_SCALE = 0.25;
00122 if (group.empty())
00123 return DEFAULT_SCALE;
00124 const robot_model::JointModelGroup *jmg = robot_model_->getJointModelGroup(group);
00125 if (!jmg)
00126 return 0.0;
00127
00128 const std::vector<std::string> &links = jmg->getLinkModelNames();
00129 if (links.empty())
00130 return DEFAULT_SCALE;
00131
00132
00133 const double inf = std::numeric_limits<double>::infinity();
00134 Eigen::Vector3d lo( inf, inf, inf);
00135 Eigen::Vector3d hi(-inf, -inf, -inf);
00136 robot_state::RobotState default_state(robot_model_);
00137 default_state.setToDefaultValues();
00138
00139 for (std::size_t i = 0 ; i < links.size() ; ++i)
00140 {
00141 const robot_model::LinkModel *lm = default_state.getLinkModel(links[i]);
00142 if (!lm)
00143 continue;
00144 const Eigen::Vector3d &ext = lm->getShapeExtentsAtOrigin();
00145
00146 Eigen::Vector3d corner1 = ext/2.0;
00147 corner1 = default_state.getGlobalLinkTransform(lm) * corner1;
00148 Eigen::Vector3d corner2 = ext/-2.0;
00149 corner2 = default_state.getGlobalLinkTransform(lm) * corner2;
00150 lo = lo.cwiseMin(corner1);
00151 hi = hi.cwiseMax(corner2);
00152 }
00153
00154
00155 double s = std::max(std::max(hi.x() - lo.x(), hi.y() - lo.y()), hi.z() - lo.z());
00156 s *= 1.73205081;
00157
00158
00159 if (s < 0.05)
00160 s = DEFAULT_SCALE;
00161 return s;
00162 }
00163
00164 void RobotInteraction::decideActiveJoints(const std::string &group)
00165 {
00166 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
00167 active_vj_.clear();
00168
00169 ROS_DEBUG_NAMED("robot_interaction", "Deciding active joints for group '%s'", group.c_str());
00170
00171 if (group.empty())
00172 return;
00173
00174 const boost::shared_ptr<const srdf::Model> &srdf = robot_model_->getSRDF();
00175 const robot_model::JointModelGroup *jmg = robot_model_->getJointModelGroup(group);
00176
00177 if (!jmg || !srdf)
00178 return;
00179
00180 std::set<std::string> used;
00181 if (jmg->hasJointModel(robot_model_->getRootJointName()))
00182 {
00183 robot_state::RobotState default_state(robot_model_);
00184 default_state.setToDefaultValues();
00185 std::vector<double> aabb;
00186 default_state.computeAABB(aabb);
00187
00188 const std::vector<srdf::Model::VirtualJoint> &vj = srdf->getVirtualJoints();
00189 for (std::size_t i = 0 ; i < vj.size() ; ++i)
00190 if (vj[i].name_ == robot_model_->getRootJointName())
00191 {
00192 if (vj[i].type_ == "planar" || vj[i].type_ == "floating")
00193 {
00194 JointInteraction v;
00195 v.connecting_link = vj[i].child_link_;
00196 v.parent_frame = vj[i].parent_frame_;
00197 if (!v.parent_frame.empty() && v.parent_frame[0] == '/')
00198 v.parent_frame = v.parent_frame.substr(1);
00199 v.joint_name = vj[i].name_;
00200 if (vj[i].type_ == "planar")
00201 v.dof = 3;
00202 else
00203 v.dof = 6;
00204
00205 v.size = std::max(std::max(aabb[1] - aabb[0], aabb[3] - aabb[2]), aabb[5] - aabb[4]);
00206 active_vj_.push_back(v);
00207 used.insert(v.joint_name);
00208 }
00209 }
00210 }
00211
00212 const std::vector<const robot_model::JointModel*> &joints = jmg->getJointModels();
00213 for (std::size_t i = 0 ; i < joints.size() ; ++i)
00214 {
00215 if ((joints[i]->getType() == robot_model::JointModel::PLANAR ||
00216 joints[i]->getType() == robot_model::JointModel::FLOATING) &&
00217 used.find(joints[i]->getName()) == used.end())
00218 {
00219 JointInteraction v;
00220 v.connecting_link = joints[i]->getChildLinkModel()->getName();
00221 if (joints[i]->getParentLinkModel())
00222 v.parent_frame = joints[i]->getParentLinkModel()->getName();
00223 v.joint_name = joints[i]->getName();
00224 if (joints[i]->getType() == robot_model::JointModel::PLANAR)
00225 v.dof = 3;
00226 else
00227 v.dof = 6;
00228
00229 v.size = computeGroupMarkerSize(group);
00230 active_vj_.push_back(v);
00231 }
00232 }
00233 }
00234
00235 void RobotInteraction::decideActiveEndEffectors(const std::string &group)
00236 {
00237 decideActiveEndEffectors(group, InteractionStyle::SIX_DOF);
00238 }
00239
00240 void RobotInteraction::decideActiveEndEffectors(const std::string &group, InteractionStyle::InteractionStyle style)
00241 {
00242 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
00243 active_eef_.clear();
00244
00245 ROS_DEBUG_NAMED("robot_interaction", "Deciding active end-effectors for group '%s'", group.c_str());
00246
00247 if (group.empty())
00248 return;
00249
00250 const boost::shared_ptr<const srdf::Model> &srdf = robot_model_->getSRDF();
00251 const robot_model::JointModelGroup *jmg = robot_model_->getJointModelGroup(group);
00252
00253 if (!jmg || !srdf)
00254 {
00255 ROS_WARN_NAMED("robot_interaction", "Unable to decide active end effector: no joint model group or no srdf model");
00256 return;
00257 }
00258
00259 const std::vector<srdf::Model::EndEffector> &eef = srdf->getEndEffectors();
00260 const std::pair<robot_model::JointModelGroup::KinematicsSolver,
00261 robot_model::JointModelGroup::KinematicsSolverMap> &smap = jmg->getGroupKinematics();
00262
00263
00264 if (smap.first)
00265 {
00266 if (eef.empty() && !jmg->getLinkModelNames().empty())
00267 {
00268
00269 EndEffectorInteraction ee;
00270 ee.parent_group = group;
00271 ee.parent_link = jmg->getLinkModelNames().back();
00272 ee.eef_group = group;
00273 ee.interaction = style;
00274 active_eef_.push_back(ee);
00275 }
00276 else
00277 {
00278 for (std::size_t i = 0 ; i < eef.size() ; ++i)
00279 if ((jmg->hasLinkModel(eef[i].parent_link_) ||
00280 jmg->getName() == eef[i].parent_group_) &&
00281 jmg->canSetStateFromIK(eef[i].parent_link_))
00282 {
00283
00284 EndEffectorInteraction ee;
00285 ee.parent_group = group;
00286 ee.parent_link = eef[i].parent_link_;
00287 ee.eef_group = eef[i].component_group_;
00288 ee.interaction = style;
00289 active_eef_.push_back(ee);
00290 }
00291 }
00292 }
00293 else if (!smap.second.empty())
00294 {
00295 for (robot_model::JointModelGroup::KinematicsSolverMap::const_iterator it = smap.second.begin() ;
00296 it != smap.second.end() ;
00297 ++it)
00298 {
00299 for (std::size_t i = 0 ; i < eef.size() ; ++i)
00300 {
00301 if ((it->first->hasLinkModel(eef[i].parent_link_) ||
00302 jmg->getName() == eef[i].parent_group_) &&
00303 it->first->canSetStateFromIK(eef[i].parent_link_))
00304 {
00305
00306 EndEffectorInteraction ee;
00307 ee.parent_group = it->first->getName();
00308 ee.parent_link = eef[i].parent_link_;
00309 ee.eef_group = eef[i].component_group_;
00310 ee.interaction = style;
00311 active_eef_.push_back(ee);
00312 break;
00313 }
00314 }
00315 }
00316 }
00317
00318 for (std::size_t i = 0 ; i < active_eef_.size() ; ++i)
00319 {
00320
00321
00322 active_eef_[i].size = active_eef_[i].eef_group == active_eef_[i].parent_group ?
00323 computeGroupMarkerSize("") :
00324 computeGroupMarkerSize(active_eef_[i].eef_group);
00325 ROS_DEBUG_NAMED("robot_interaction",
00326 "Found active end-effector '%s', of scale %lf",
00327 active_eef_[i].eef_group.c_str(),
00328 active_eef_[i].size);
00329 }
00330 }
00331
00332 void RobotInteraction::clear()
00333 {
00334 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
00335 active_eef_.clear();
00336 active_vj_.clear();
00337 active_generic_.clear();
00338 clearInteractiveMarkersUnsafe();
00339 publishInteractiveMarkers();
00340 }
00341
00342 void RobotInteraction::clearInteractiveMarkers()
00343 {
00344 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
00345 clearInteractiveMarkersUnsafe();
00346 }
00347
00348 void RobotInteraction::clearInteractiveMarkersUnsafe()
00349 {
00350 handlers_.clear();
00351 shown_markers_.clear();
00352 int_marker_move_subscribers_.clear();
00353 int_marker_move_topics_.clear();
00354 int_marker_names_.clear();
00355 int_marker_server_->clear();
00356 }
00357
00358 void RobotInteraction::addEndEffectorMarkers(
00359 const ::robot_interaction::InteractionHandlerPtr &handler,
00360 const EndEffectorInteraction& eef,
00361 visualization_msgs::InteractiveMarker& im,
00362 bool position,
00363 bool orientation)
00364 {
00365 geometry_msgs::Pose pose;
00366 pose.orientation.w = 1;
00367 addEndEffectorMarkers(handler, eef, pose, im, position, orientation);
00368 }
00369
00370 void RobotInteraction::addEndEffectorMarkers(
00371 const ::robot_interaction::InteractionHandlerPtr &handler,
00372 const EndEffectorInteraction& eef,
00373 const geometry_msgs::Pose& im_to_eef,
00374 visualization_msgs::InteractiveMarker& im,
00375 bool position,
00376 bool orientation)
00377 {
00378 if (eef.parent_group == eef.eef_group || !robot_model_->hasLinkModel(eef.parent_link))
00379 return;
00380
00381 visualization_msgs::InteractiveMarkerControl m_control;
00382 m_control.always_visible = false;
00383 if (position && orientation)
00384 m_control.interaction_mode = m_control.MOVE_ROTATE_3D;
00385 else if (orientation)
00386 m_control.interaction_mode = m_control.ROTATE_3D;
00387 else
00388 m_control.interaction_mode = m_control.MOVE_3D;
00389
00390 std_msgs::ColorRGBA marker_color;
00391 const float *color = handler->inError(eef) ? END_EFFECTOR_UNREACHABLE_COLOR : END_EFFECTOR_REACHABLE_COLOR;
00392 marker_color.r = color[0];
00393 marker_color.g = color[1];
00394 marker_color.b = color[2];
00395 marker_color.a = color[3];
00396
00397 robot_state::RobotStateConstPtr rstate = handler->getState();
00398 const std::vector<std::string> &link_names = rstate->getJointModelGroup(eef.eef_group)->getLinkModelNames();
00399 visualization_msgs::MarkerArray marker_array;
00400 rstate->getRobotMarkers(marker_array, link_names, marker_color, eef.eef_group, ros::Duration());
00401 tf::Pose tf_root_to_link;
00402 tf::poseEigenToTF(rstate->getGlobalLinkTransform(eef.parent_link), tf_root_to_link);
00403
00404 rstate.reset();
00405
00406 for (std::size_t i = 0 ; i < marker_array.markers.size() ; ++i)
00407 {
00408 marker_array.markers[i].header = im.header;
00409 marker_array.markers[i].mesh_use_embedded_materials = true;
00410
00411 tf::Pose tf_root_to_im, tf_root_to_mesh, tf_im_to_eef;
00412 tf::poseMsgToTF(im.pose, tf_root_to_im);
00413 tf::poseMsgToTF(marker_array.markers[i].pose, tf_root_to_mesh);
00414 tf::poseMsgToTF(im_to_eef, tf_im_to_eef);
00415 tf::Pose tf_eef_to_mesh = tf_root_to_link.inverse() * tf_root_to_mesh;
00416 tf::Pose tf_im_to_mesh = tf_im_to_eef * tf_eef_to_mesh;
00417 tf::Pose tf_root_to_mesh_new = tf_root_to_im * tf_im_to_mesh;
00418 tf::poseTFToMsg(tf_root_to_mesh_new, marker_array.markers[i].pose);
00419
00420 m_control.markers.push_back(marker_array.markers[i]);
00421 }
00422
00423 im.controls.push_back(m_control);
00424 }
00425
00426 static inline std::string getMarkerName(
00427 const ::robot_interaction::InteractionHandlerPtr &handler,
00428 const EndEffectorInteraction &eef)
00429 {
00430 return "EE:" + handler->getName() + "_" + eef.parent_link;
00431 }
00432
00433 static inline std::string getMarkerName(
00434 const ::robot_interaction::InteractionHandlerPtr &handler,
00435 const JointInteraction &vj)
00436 {
00437 return "JJ:" + handler->getName() + "_" + vj.connecting_link;
00438 }
00439
00440 static inline std::string getMarkerName(
00441 const ::robot_interaction::InteractionHandlerPtr &handler, const GenericInteraction &g)
00442 {
00443 return "GG:" + handler->getName() + "_" + g.marker_name_suffix;
00444 }
00445
00446 void RobotInteraction::addInteractiveMarkers(
00447 const ::robot_interaction::InteractionHandlerPtr &handler,
00448 const double marker_scale)
00449 {
00450 handler->setRobotInteraction(this);
00451
00452 std::vector<visualization_msgs::InteractiveMarker> ims;
00453 ros::NodeHandle nh;
00454 {
00455 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
00456 robot_state::RobotStateConstPtr s = handler->getState();
00457
00458 for (std::size_t i = 0 ; i < active_generic_.size() ; ++i)
00459 {
00460 visualization_msgs::InteractiveMarker im;
00461 if (active_generic_[i].construct_marker(*s, im))
00462 {
00463 im.name = getMarkerName(handler, active_generic_[i]);
00464 shown_markers_[im.name] = i;
00465 ims.push_back(im);
00466 ROS_DEBUG_NAMED("robot_interaction",
00467 "Publishing interactive marker %s (size = %lf)",
00468 im.name.c_str(),
00469 im.scale);
00470 }
00471 }
00472 ros::NodeHandle nh;
00473
00474 for (std::size_t i = 0 ; i < active_eef_.size() ; ++i)
00475 {
00476
00477 geometry_msgs::PoseStamped pose;
00478 geometry_msgs::Pose control_to_eef_tf;
00479 pose.header.frame_id = robot_model_->getModelFrame();
00480 pose.header.stamp = ros::Time::now();
00481 computeMarkerPose(handler, active_eef_[i], *s, pose.pose, control_to_eef_tf);
00482
00483 std::string marker_name = getMarkerName(handler, active_eef_[i]);
00484 shown_markers_[marker_name] = i;
00485
00486
00487 double mscale = marker_scale < std::numeric_limits<double>::epsilon() ? active_eef_[i].size : marker_scale;
00488
00489 visualization_msgs::InteractiveMarker im = makeEmptyInteractiveMarker(marker_name, pose, mscale);
00490 if (handler && handler->getControlsVisible())
00491 {
00492 if (active_eef_[i].interaction & EEF_POSITION_ARROWS)
00493 addPositionControl(im, active_eef_[i].interaction & EEF_FIXED);
00494 if (active_eef_[i].interaction & EEF_ORIENTATION_CIRCLES)
00495 addOrientationControl(im, active_eef_[i].interaction & EEF_FIXED);
00496 if (active_eef_[i].interaction & (EEF_POSITION_SPHERE|EEF_ORIENTATION_SPHERE))
00497 {
00498 std_msgs::ColorRGBA color;
00499 color.r = 0;
00500 color.g = 1;
00501 color.b = 1;
00502 color.a = 0.5;
00503 addViewPlaneControl(im,
00504 mscale * 0.25,
00505 color,
00506 active_eef_[i].interaction&EEF_POSITION_SPHERE,
00507 active_eef_[i].interaction&EEF_ORIENTATION_SPHERE);
00508 }
00509 }
00510 if (handler &&
00511 handler->getMeshesVisible() &&
00512 (active_eef_[i].interaction & (EEF_POSITION_EEF|EEF_ORIENTATION_EEF)))
00513 addEndEffectorMarkers(handler,
00514 active_eef_[i],
00515 control_to_eef_tf,
00516 im,
00517 active_eef_[i].interaction & EEF_POSITION_EEF,
00518 active_eef_[i].interaction & EEF_ORIENTATION_EEF);
00519 ims.push_back(im);
00520 registerMoveInteractiveMarkerTopic(
00521 marker_name,
00522 handler->getName() + "_" + active_eef_[i].parent_link);
00523 ROS_DEBUG_NAMED("robot_interaction",
00524 "Publishing interactive marker %s (size = %lf)",
00525 marker_name.c_str(),
00526 mscale);
00527 }
00528 for (std::size_t i = 0 ; i < active_vj_.size() ; ++i)
00529 {
00530 geometry_msgs::PoseStamped pose;
00531 pose.header.frame_id = robot_model_->getModelFrame();
00532 pose.header.stamp = ros::Time::now();
00533 tf::poseEigenToMsg(s->getGlobalLinkTransform(active_vj_[i].connecting_link), pose.pose);
00534 std::string marker_name = getMarkerName(handler, active_vj_[i]);
00535 shown_markers_[marker_name] = i;
00536
00537
00538 double mscale = marker_scale < std::numeric_limits<double>::epsilon() ? active_vj_[i].size : marker_scale;
00539
00540 visualization_msgs::InteractiveMarker im = makeEmptyInteractiveMarker(marker_name, pose, mscale);
00541 if (handler && handler->getControlsVisible())
00542 {
00543 if (active_vj_[i].dof == 3)
00544 addPlanarXYControl(im, false);
00545 else
00546 add6DOFControl(im, false);
00547 }
00548 ims.push_back(im);
00549 registerMoveInteractiveMarkerTopic(marker_name, handler->getName() + "_" + active_vj_[i].connecting_link);
00550 ROS_DEBUG_NAMED("robot_interaction",
00551 "Publishing interactive marker %s (size = %lf)",
00552 marker_name.c_str(),
00553 mscale);
00554 }
00555 handlers_[handler->getName()] = handler;
00556 }
00557
00558
00559
00560
00561 for (std::size_t i = 0 ; i < ims.size() ; ++i)
00562 {
00563 int_marker_server_->insert(ims[i]);
00564 int_marker_server_->setCallback(ims[i].name,
00565 boost::bind(&RobotInteraction::processInteractiveMarkerFeedback,
00566 this,
00567 _1));
00568
00569
00570 if (boost::shared_ptr<interactive_markers::MenuHandler> mh = handler->getMenuHandler())
00571 mh->apply(*int_marker_server_, ims[i].name);
00572 }
00573 }
00574
00575 void RobotInteraction::registerMoveInteractiveMarkerTopic(
00576 const std::string marker_name, const std::string& name)
00577 {
00578 ros::NodeHandle nh;
00579 std::stringstream ss;
00580 ss << "/rviz/moveit/move_marker/";
00581 ss << name;
00582 int_marker_move_topics_.push_back(ss.str());
00583 int_marker_names_.push_back(marker_name);
00584 }
00585
00586 void RobotInteraction::toggleMoveInteractiveMarkerTopic(bool enable)
00587 {
00588 if (enable)
00589 {
00590 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
00591 if (int_marker_move_subscribers_.size() == 0)
00592 {
00593 ros::NodeHandle nh;
00594 for (size_t i = 0; i < int_marker_move_topics_.size(); i++) {
00595 std::string topic_name = int_marker_move_topics_[i];
00596 std::string marker_name = int_marker_names_[i];
00597 int_marker_move_subscribers_.push_back(
00598 nh.subscribe<geometry_msgs::PoseStamped>
00599 (topic_name, 1, boost::bind(&RobotInteraction::moveInteractiveMarker,
00600 this, marker_name, _1)));
00601 }
00602 }
00603 }
00604 else
00605 {
00606 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
00607 int_marker_move_subscribers_.clear();
00608 }
00609 }
00610
00611 void RobotInteraction::computeMarkerPose(
00612 const ::robot_interaction::InteractionHandlerPtr &handler,
00613 const EndEffectorInteraction &eef,
00614 const robot_state::RobotState &robot_state,
00615 geometry_msgs::Pose &pose,
00616 geometry_msgs::Pose &control_to_eef_tf) const
00617 {
00618
00619 tf::Transform tf_root_to_link, tf_root_to_control;
00620 tf::poseEigenToTF(robot_state.getGlobalLinkTransform(eef.parent_link), tf_root_to_link);
00621
00622 geometry_msgs::Pose msg_link_to_control;
00623 if (handler->getPoseOffset(eef, msg_link_to_control))
00624 {
00625 tf::Transform tf_link_to_control;
00626 tf::poseMsgToTF(msg_link_to_control, tf_link_to_control);
00627
00628 tf_root_to_control = tf_root_to_link * tf_link_to_control;
00629 tf::poseTFToMsg(tf_link_to_control.inverse(), control_to_eef_tf);
00630 }
00631 else
00632 {
00633 tf_root_to_control = tf_root_to_link;
00634 control_to_eef_tf.orientation.x = 0.0;
00635 control_to_eef_tf.orientation.y = 0.0;
00636 control_to_eef_tf.orientation.z = 0.0;
00637 control_to_eef_tf.orientation.w = 1.0;
00638 }
00639
00640 tf::poseTFToMsg(tf_root_to_control, pose);
00641 }
00642
00643 void RobotInteraction::updateInteractiveMarkers(const ::robot_interaction::InteractionHandlerPtr &handler)
00644 {
00645 handler->setRobotInteraction(this);
00646 std::map<std::string, geometry_msgs::Pose> pose_updates;
00647 {
00648 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
00649
00650 robot_state::RobotStateConstPtr s = handler->getState();
00651 for (std::size_t i = 0 ; i < active_eef_.size() ; ++i)
00652 {
00653 std::string marker_name = getMarkerName(handler, active_eef_[i]);
00654 geometry_msgs::Pose control_to_eef_tf;
00655 computeMarkerPose(handler, active_eef_[i], *s, pose_updates[marker_name], control_to_eef_tf);
00656 }
00657
00658 for (std::size_t i = 0 ; i < active_vj_.size() ; ++i)
00659 {
00660 std::string marker_name = getMarkerName(handler, active_vj_[i]);
00661 tf::poseEigenToMsg(s->getGlobalLinkTransform(active_vj_[i].connecting_link), pose_updates[marker_name]);
00662 }
00663
00664 for (std::size_t i = 0 ; i < active_generic_.size() ; ++i)
00665 {
00666 std::string marker_name = getMarkerName(handler, active_generic_[i]);
00667 geometry_msgs::Pose pose;
00668 if (active_generic_[i].update_pose && active_generic_[i].update_pose(*s, pose))
00669 pose_updates[marker_name] = pose;
00670 }
00671 }
00672 for (std::map<std::string, geometry_msgs::Pose>::const_iterator it = pose_updates.begin() ;
00673 it != pose_updates.end() ;
00674 ++it)
00675 int_marker_server_->setPose(it->first, it->second);
00676 int_marker_server_->applyChanges();
00677 }
00678
00679 void RobotInteraction::publishInteractiveMarkers()
00680 {
00681
00682 int_marker_server_->applyChanges();
00683 }
00684
00685 bool RobotInteraction::showingMarkers(const ::robot_interaction::InteractionHandlerPtr &handler)
00686 {
00687 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
00688
00689 for (std::size_t i = 0 ; i < active_eef_.size() ; ++i)
00690 if (shown_markers_.find(getMarkerName(handler, active_eef_[i])) == shown_markers_.end())
00691 return false;
00692 for (std::size_t i = 0 ; i < active_vj_.size() ; ++i)
00693 if (shown_markers_.find(getMarkerName(handler, active_vj_[i])) == shown_markers_.end())
00694 return false;
00695 for (std::size_t i = 0 ; i < active_generic_.size() ; ++i)
00696 if (shown_markers_.find(getMarkerName(handler, active_generic_[i])) == shown_markers_.end())
00697 return false;
00698 return true;
00699 }
00700
00701
00702 bool RobotInteraction::updateState(
00703 robot_state::RobotState &state,
00704 const EndEffectorInteraction &eef,
00705 const geometry_msgs::Pose &pose,
00706 unsigned int attempts,
00707 double ik_timeout,
00708 const robot_state::GroupStateValidityCallbackFn &validity_callback,
00709 const kinematics::KinematicsQueryOptions &kinematics_query_options)
00710 {
00711 if (state.setFromIK(state.getJointModelGroup(eef.parent_group), pose, eef.parent_link,
00712 kinematics_query_options.lock_redundant_joints ? 1 : attempts,
00713 ik_timeout, validity_callback, kinematics_query_options))
00714 {
00715 state.update();
00716 return true;
00717 }
00718 return false;
00719 }
00720
00721 void RobotInteraction::moveInteractiveMarker(const std::string name, const geometry_msgs::PoseStampedConstPtr& msg)
00722 {
00723 std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(name);
00724 if (it != shown_markers_.end())
00725 {
00726 visualization_msgs::InteractiveMarkerFeedback::Ptr feedback (new visualization_msgs::InteractiveMarkerFeedback);
00727 feedback->header = msg->header;
00728 feedback->marker_name = name;
00729 feedback->pose = msg->pose;
00730 feedback->event_type = visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE;
00731 processInteractiveMarkerFeedback(feedback);
00732 {
00733 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
00734 int_marker_server_->setPose(name, msg->pose, msg->header);
00735 int_marker_server_->applyChanges();
00736 }
00737 }
00738 }
00739
00740 void RobotInteraction::processInteractiveMarkerFeedback(
00741 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
00742 {
00743
00744 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
00745 std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(feedback->marker_name);
00746 if (it == shown_markers_.end())
00747 {
00748 ROS_ERROR("Unknown marker name: '%s' (not published by RobotInteraction class)", feedback->marker_name.c_str());
00749 return;
00750 }
00751
00752 std::size_t u = feedback->marker_name.find_first_of("_");
00753 if (u == std::string::npos || u < 4)
00754 {
00755 ROS_ERROR("Invalid marker name: '%s'", feedback->marker_name.c_str());
00756 return;
00757 }
00758
00759 feedback_map_[feedback->marker_name] = feedback;
00760 new_feedback_condition_.notify_all();
00761 }
00762
00763 void RobotInteraction::processingThread()
00764 {
00765 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
00766
00767 while (run_processing_thread_ && ros::ok())
00768 {
00769 while (feedback_map_.empty() && run_processing_thread_ && ros::ok())
00770 new_feedback_condition_.wait(ulock);
00771
00772 while (!feedback_map_.empty() && ros::ok())
00773 {
00774 visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback = feedback_map_.begin()->second;
00775 feedback_map_.erase(feedback_map_.begin());
00776 ROS_DEBUG_NAMED("robot_interaction",
00777 "Processing feedback from map for marker [%s]",
00778 feedback->marker_name.c_str());
00779
00780 std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(feedback->marker_name);
00781 if (it == shown_markers_.end())
00782 {
00783 ROS_ERROR("Unknown marker name: '%s' (not published by RobotInteraction class) "
00784 "(should never have ended up in the feedback_map!)",
00785 feedback->marker_name.c_str());
00786 continue;
00787 }
00788 std::size_t u = feedback->marker_name.find_first_of("_");
00789 if (u == std::string::npos || u < 4)
00790 {
00791 ROS_ERROR("Invalid marker name: '%s' (should never have ended up in the feedback_map!)",
00792 feedback->marker_name.c_str());
00793 continue;
00794 }
00795 std::string marker_class = feedback->marker_name.substr(0, 2);
00796 std::string handler_name = feedback->marker_name.substr(3, u - 3);
00797 std::map<std::string, ::robot_interaction::InteractionHandlerPtr>::const_iterator jt =
00798 handlers_.find(handler_name);
00799 if (jt == handlers_.end())
00800 {
00801 ROS_ERROR("Interactive Marker Handler '%s' is not known.", handler_name.c_str());
00802 continue;
00803 }
00804
00805
00806 try
00807 {
00808 if (marker_class == "EE")
00809 {
00810
00811 EndEffectorInteraction eef = active_eef_[it->second];
00812 ::robot_interaction::InteractionHandlerPtr ih = jt->second;
00813 marker_access_lock_.unlock();
00814 try
00815 {
00816 ih->handleEndEffector(eef, feedback);
00817 }
00818 catch(std::runtime_error &ex)
00819 {
00820 ROS_ERROR("Exception caught while handling end-effector update: %s", ex.what());
00821 }
00822 catch(...)
00823 {
00824 ROS_ERROR("Exception caught while handling end-effector update");
00825 }
00826 marker_access_lock_.lock();
00827 }
00828 else
00829 if (marker_class == "JJ")
00830 {
00831
00832 JointInteraction vj = active_vj_[it->second];
00833 ::robot_interaction::InteractionHandlerPtr ih = jt->second;
00834 marker_access_lock_.unlock();
00835 try
00836 {
00837 ih->handleJoint(vj, feedback);
00838 }
00839 catch(std::runtime_error &ex)
00840 {
00841 ROS_ERROR("Exception caught while handling joint update: %s", ex.what());
00842 }
00843 catch(...)
00844 {
00845 ROS_ERROR("Exception caught while handling joint update");
00846 }
00847 marker_access_lock_.lock();
00848 }
00849 else
00850 if (marker_class == "GG")
00851 {
00852 ::robot_interaction::InteractionHandlerPtr ih = jt->second;
00853 GenericInteraction g = active_generic_[it->second];
00854 marker_access_lock_.unlock();
00855 try
00856 {
00857 ih->handleGeneric(g, feedback);
00858 }
00859 catch(std::runtime_error &ex)
00860 {
00861 ROS_ERROR("Exception caught while handling joint update: %s", ex.what());
00862 }
00863 catch(...)
00864 {
00865 ROS_ERROR("Exception caught while handling joint update");
00866 }
00867 marker_access_lock_.lock();
00868 }
00869 else
00870 ROS_ERROR("Unknown marker class ('%s') for marker '%s'",
00871 marker_class.c_str(),
00872 feedback->marker_name.c_str());
00873 }
00874 catch (std::runtime_error &ex)
00875 {
00876 ROS_ERROR("Exception caught while processing event: %s", ex.what());
00877 }
00878 catch (...)
00879 {
00880 ROS_ERROR("Exception caught while processing event");
00881 }
00882 }
00883 }
00884 }
00885
00886
00887 void RobotInteraction::decideActiveComponents(const std::string &group, EndEffectorInteractionStyle style)
00888 {
00889 decideActiveComponents(group, (InteractionStyle::InteractionStyle)(int)style);
00890 }
00891
00892
00893 void RobotInteraction::decideActiveEndEffectors(const std::string &group, EndEffectorInteractionStyle style)
00894 {
00895 decideActiveEndEffectors(group, (InteractionStyle::InteractionStyle)(int)style);
00896 }
00897
00898 }