47 #include <boost/lexical_cast.hpp> 48 #include <boost/math/constants/constants.hpp> 49 #include <boost/algorithm/string.hpp> 55 #include <Eigen/Geometry> 95 ROS_INFO_NAMED(
"robot_interaction",
"No active joints or end effectors found for group '%s'. " 96 "Make sure that kinematics.yaml is loaded in this node's namespace.",
102 const std::string& name)
117 const robot_model::LinkModel* lm =
robot_model_->getLinkModel(link);
122 Eigen::Vector3d ext = lm->getShapeExtentsAtOrigin();
124 Eigen::MatrixXd::Index maxIndex;
125 ext.maxCoeff(&maxIndex);
127 size = 1.01 * ext.norm();
134 lm = lm->getParentLinkModel();
148 return DEFAULT_SCALE;
149 const robot_model::JointModelGroup* jmg =
robot_model_->getJointModelGroup(group);
153 const std::vector<std::string>& links = jmg->getLinkModelNames();
155 return DEFAULT_SCALE;
159 for (std::size_t i = 0; i < links.size(); ++i)
161 const robot_model::LinkModel* lm =
robot_model_->getLinkModel(links[i]);
164 Eigen::Vector3d ext = lm->getShapeExtentsAtOrigin();
167 Eigen::MatrixXd::Index maxIndex;
168 ext.maxCoeff(&maxIndex);
170 size = std::max(size, 1.01 * ext.norm());
190 ROS_DEBUG_NAMED(
"robot_interaction",
"Deciding active joints for group '%s'", group.c_str());
193 const robot_model::JointModelGroup* jmg =
robot_model_->getJointModelGroup(group);
198 std::set<std::string> used;
199 if (jmg->hasJointModel(
robot_model_->getRootJointName()))
202 default_state.setToDefaultValues();
203 std::vector<double> aabb;
204 default_state.computeAABB(aabb);
206 const std::vector<srdf::Model::VirtualJoint>& vj = srdf->getVirtualJoints();
207 for (std::size_t i = 0; i < vj.size(); ++i)
210 if (vj[i].type_ ==
"planar" || vj[i].type_ ==
"floating")
218 if (vj[i].type_ ==
"planar")
223 v.
size = std::max(std::max(aabb[1] - aabb[0], aabb[3] - aabb[2]), aabb[5] - aabb[4]);
230 const std::vector<const robot_model::JointModel*>& joints = jmg->getJointModels();
231 for (std::size_t i = 0; i < joints.size(); ++i)
233 if ((joints[i]->getType() == robot_model::JointModel::PLANAR ||
234 joints[i]->getType() == robot_model::JointModel::FLOATING) &&
235 used.find(joints[i]->
getName()) == used.end())
239 if (joints[i]->getParentLinkModel())
240 v.
parent_frame = joints[i]->getParentLinkModel()->getName();
242 if (joints[i]->getType() == robot_model::JointModel::PLANAR)
266 ROS_DEBUG_NAMED(
"robot_interaction",
"Deciding active end-effectors for group '%s'", group.c_str());
269 const robot_model::JointModelGroup* jmg =
robot_model_->getJointModelGroup(group);
273 ROS_WARN_NAMED(
"robot_interaction",
"Unable to decide active end effector: no joint model group or no srdf model");
277 const std::vector<srdf::Model::EndEffector>& eef = srdf->getEndEffectors();
278 const std::pair<robot_model::JointModelGroup::KinematicsSolver, robot_model::JointModelGroup::KinematicsSolverMap>&
279 smap = jmg->getGroupKinematics();
284 for (std::size_t i = 0; i < eef.size(); ++i)
285 if ((jmg->hasLinkModel(eef[i].parent_link_) || jmg->getName() == eef[i].parent_group_) &&
286 jmg->canSetStateFromIK(eef[i].parent_link_))
298 if (
active_eef_.empty() && !jmg->getLinkModelNames().empty())
308 else if (!smap.second.empty())
310 for (robot_model::JointModelGroup::KinematicsSolverMap::const_iterator it = smap.second.begin();
311 it != smap.second.end(); ++it)
313 for (std::size_t i = 0; i < eef.size(); ++i)
315 if ((it->first->hasLinkModel(eef[i].parent_link_) || jmg->getName() == eef[i].parent_group_) &&
316 it->first->canSetStateFromIK(eef[i].parent_link_))
331 for (std::size_t i = 0; i <
active_eef_.size(); ++i)
338 ROS_DEBUG_NAMED(
"robot_interaction",
"Found active end-effector '%s', of scale %lf",
374 visualization_msgs::InteractiveMarker& im,
bool position,
bool orientation)
376 geometry_msgs::Pose pose;
377 pose.orientation.w = 1;
383 visualization_msgs::InteractiveMarker& im,
bool position,
bool orientation)
388 visualization_msgs::InteractiveMarkerControl m_control;
389 m_control.always_visible =
false;
390 if (position && orientation)
391 m_control.interaction_mode = m_control.MOVE_ROTATE_3D;
392 else if (orientation)
393 m_control.interaction_mode = m_control.ROTATE_3D;
395 m_control.interaction_mode = m_control.MOVE_3D;
397 std_msgs::ColorRGBA marker_color;
399 marker_color.r = color[0];
400 marker_color.g = color[1];
401 marker_color.b = color[2];
402 marker_color.a = color[3];
404 robot_state::RobotStateConstPtr rstate = handler->getState();
405 const std::vector<std::string>& link_names = rstate->getJointModelGroup(eef.
eef_group)->getLinkModelNames();
406 visualization_msgs::MarkerArray marker_array;
413 for (std::size_t i = 0; i < marker_array.markers.size(); ++i)
415 marker_array.markers[i].header = im.header;
416 marker_array.markers[i].mesh_use_embedded_materials =
true;
418 tf::Pose tf_root_to_im, tf_root_to_mesh, tf_im_to_eef;
423 tf::Pose tf_im_to_mesh = tf_im_to_eef * tf_eef_to_mesh;
424 tf::Pose tf_root_to_mesh_new = tf_root_to_im * tf_im_to_mesh;
427 m_control.markers.push_back(marker_array.markers[i]);
430 im.controls.push_back(m_control);
433 static inline std::string
getMarkerName(const ::robot_interaction::InteractionHandlerPtr& handler,
436 return "EE:" + handler->getName() +
"_" + eef.
parent_link;
439 static inline std::string
getMarkerName(const ::robot_interaction::InteractionHandlerPtr& handler,
445 static inline std::string
getMarkerName(const ::robot_interaction::InteractionHandlerPtr& handler,
452 const double marker_scale)
454 handler->setRobotInteraction(
this);
456 std::vector<visualization_msgs::InteractiveMarker> ims;
460 robot_state::RobotStateConstPtr
s = handler->getState();
464 visualization_msgs::InteractiveMarker im;
470 ROS_DEBUG_NAMED(
"robot_interaction",
"Publishing interactive marker %s (size = %lf)", im.name.c_str(),
476 for (std::size_t i = 0; i <
active_eef_.size(); ++i)
478 geometry_msgs::PoseStamped pose;
479 geometry_msgs::Pose control_to_eef_tf;
488 double mscale = marker_scale < std::numeric_limits<double>::epsilon() ?
active_eef_[i].size : marker_scale;
491 if (handler && handler->getControlsVisible())
499 std_msgs::ColorRGBA color;
508 if (handler && handler->getMeshesVisible() &&
515 ROS_DEBUG_NAMED(
"robot_interaction",
"Publishing interactive marker %s (size = %lf)", marker_name.c_str(),
518 for (std::size_t i = 0; i <
active_vj_.size(); ++i)
520 geometry_msgs::PoseStamped pose;
528 double mscale = marker_scale < std::numeric_limits<double>::epsilon() ?
active_vj_[i].size : marker_scale;
531 if (handler && handler->getControlsVisible())
540 ROS_DEBUG_NAMED(
"robot_interaction",
"Publishing interactive marker %s (size = %lf)", marker_name.c_str(),
549 for (std::size_t i = 0; i < ims.size(); ++i)
556 if (std::shared_ptr<interactive_markers::MenuHandler> mh = handler->getMenuHandler())
564 std::stringstream ss;
565 ss <<
"/rviz/moveit/move_marker/";
597 geometry_msgs::Pose& pose, geometry_msgs::Pose& control_to_eef_tf)
const 603 geometry_msgs::Pose msg_link_to_control;
604 if (handler->getPoseOffset(eef, msg_link_to_control))
609 tf_root_to_control = tf_root_to_link * tf_link_to_control;
614 tf_root_to_control = tf_root_to_link;
615 control_to_eef_tf.orientation.x = 0.0;
616 control_to_eef_tf.orientation.y = 0.0;
617 control_to_eef_tf.orientation.z = 0.0;
618 control_to_eef_tf.orientation.w = 1.0;
626 handler->setRobotInteraction(
this);
627 std::string root_link;
628 std::map<std::string, geometry_msgs::Pose> pose_updates;
632 robot_state::RobotStateConstPtr
s = handler->getState();
633 root_link = s->getRobotModel()->getModelFrame();
635 for (std::size_t i = 0; i <
active_eef_.size(); ++i)
638 geometry_msgs::Pose control_to_eef_tf;
642 for (std::size_t i = 0; i <
active_vj_.size(); ++i)
651 geometry_msgs::Pose pose;
653 pose_updates[marker_name] = pose;
657 std_msgs::Header header;
658 header.frame_id = root_link;
659 for (std::map<std::string, geometry_msgs::Pose>::const_iterator it = pose_updates.begin(); it != pose_updates.end();
675 for (std::size_t i = 0; i <
active_eef_.size(); ++i)
678 for (std::size_t i = 0; i <
active_vj_.size(); ++i)
689 const geometry_msgs::Pose& pose,
unsigned int attempts,
double ik_timeout,
690 const robot_state::GroupStateValidityCallbackFn& validity_callback,
695 kinematics_query_options))
705 std::map<std::string, std::size_t>::const_iterator it =
shown_markers_.find(name);
708 visualization_msgs::InteractiveMarkerFeedback::Ptr feedback(
new visualization_msgs::InteractiveMarkerFeedback);
709 feedback->header = msg->header;
710 feedback->marker_name = name;
711 feedback->pose = msg->pose;
712 feedback->event_type = visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE;
723 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
727 std::map<std::string, std::size_t>::const_iterator it =
shown_markers_.find(feedback->marker_name);
730 ROS_ERROR(
"Unknown marker name: '%s' (not published by RobotInteraction class)", feedback->marker_name.c_str());
734 std::size_t u = feedback->marker_name.find_first_of(
"_");
735 if (u == std::string::npos || u < 4)
737 ROS_ERROR(
"Invalid marker name: '%s'", feedback->marker_name.c_str());
756 visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback =
feedback_map_.begin()->second;
758 ROS_DEBUG_NAMED(
"robot_interaction",
"Processing feedback from map for marker [%s]",
759 feedback->marker_name.c_str());
761 std::map<std::string, std::size_t>::const_iterator it =
shown_markers_.find(feedback->marker_name);
764 ROS_ERROR(
"Unknown marker name: '%s' (not published by RobotInteraction class) " 765 "(should never have ended up in the feedback_map!)",
766 feedback->marker_name.c_str());
769 std::size_t u = feedback->marker_name.find_first_of(
"_");
770 if (u == std::string::npos || u < 4)
772 ROS_ERROR(
"Invalid marker name: '%s' (should never have ended up in the feedback_map!)",
773 feedback->marker_name.c_str());
776 std::string marker_class = feedback->marker_name.substr(0, 2);
777 std::string handler_name = feedback->marker_name.substr(3, u - 3);
778 std::map<std::string, ::robot_interaction::InteractionHandlerPtr>::const_iterator jt =
782 ROS_ERROR(
"Interactive Marker Handler '%s' is not known.", handler_name.c_str());
789 if (marker_class ==
"EE")
793 ::robot_interaction::InteractionHandlerPtr ih = jt->second;
797 ih->handleEndEffector(eef, feedback);
799 catch (std::exception& ex)
801 ROS_ERROR(
"Exception caught while handling end-effector update: %s", ex.what());
805 else if (marker_class ==
"JJ")
809 ::robot_interaction::InteractionHandlerPtr ih = jt->second;
813 ih->handleJoint(vj, feedback);
815 catch (std::exception& ex)
817 ROS_ERROR(
"Exception caught while handling joint update: %s", ex.what());
821 else if (marker_class ==
"GG")
823 ::robot_interaction::InteractionHandlerPtr ih = jt->second;
828 ih->handleGeneric(g, feedback);
830 catch (std::exception& ex)
832 ROS_ERROR(
"Exception caught while handling joint update: %s", ex.what());
837 ROS_ERROR(
"Unknown marker class ('%s') for marker '%s'", marker_class.c_str(), feedback->marker_name.c_str());
839 catch (std::exception& ex)
841 ROS_ERROR(
"Exception caught while processing event: %s", ex.what());
boost::condition_variable new_feedback_condition_
void clearInteractiveMarkers()
std::vector< JointInteraction > active_vj_
void moveInteractiveMarker(const std::string name, const geometry_msgs::PoseStampedConstPtr &msg)
visualization_msgs::InteractiveMarker makeEmptyInteractiveMarker(const std::string &name, const geometry_msgs::PoseStamped &stamped, double scale)
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
void poseEigenToTF(const Eigen::Affine3d &e, tf::Pose &t)
#define ROS_INFO_NAMED(name,...)
std::string parent_link
The name of the link in the parent group that connects to the end-effector.
InteractionStyle::InteractionStyle interaction
Which degrees of freedom to enable for the end-effector.
std::map< std::string,::robot_interaction::InteractionHandlerPtr > handlers_
#define ROS_WARN_NAMED(name,...)
void registerMoveInteractiveMarkerTopic(const std::string marker_name, const std::string &name)
double computeGroupMarkerSize(const std::string &group)
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void addPlanarXYControl(visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
void decideActiveJoints(const std::string &group)
virtual ~RobotInteraction()
static bool updateState(robot_state::RobotState &state, const EndEffectorInteraction &eef, const geometry_msgs::Pose &pose, unsigned int attempts, double ik_timeout, const robot_state::GroupStateValidityCallbackFn &validity_callback=robot_state::GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &kinematics_query_options=kinematics::KinematicsQueryOptions())
void addPositionControl(visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
std::string getName(void *handle)
void toggleMoveInteractiveMarkerTopic(bool enable)
EndEffectorInteractionStyle
bool lock_redundant_joints
std::vector< ros::Subscriber > int_marker_move_subscribers_
void clearInteractiveMarkersUnsafe()
static const float END_EFFECTOR_UNREACHABLE_COLOR[4]
void addViewPlaneControl(visualization_msgs::InteractiveMarker &int_marker, double radius, const std_msgs::ColorRGBA &color, bool position=true, bool orientation=true)
double size
The size of the connecting link (diameter of enclosing sphere)
static const double DEFAULT_SCALE
double computeLinkMarkerSize(const std::string &link)
#define ROS_DEBUG_NAMED(name,...)
std::vector< std::string > int_marker_names_
robot_model::RobotModelConstPtr robot_model_
interactive_markers::InteractiveMarkerServer * int_marker_server_
void addEndEffectorMarkers(const ::robot_interaction::InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, visualization_msgs::InteractiveMarker &im, bool position=true, bool orientation=true)
std::string eef_group
The name of the group that defines the group joints.
void addOrientationControl(visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
void decideActiveEndEffectors(const std::string &group)
std::vector< std::string > int_marker_move_topics_
static const float END_EFFECTOR_REACHABLE_COLOR[4]
std::map< std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr > feedback_map_
std::string parent_group
The name of the group that sustains the end-effector (usually an arm)
boost::function< bool(const robot_state::RobotState &, geometry_msgs::Pose &)> InteractiveMarkerUpdateFn
boost::function< bool(robot_state::RobotState &state, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)> ProcessFeedbackFn
RobotInteraction(const robot_model::RobotModelConstPtr &kmodel, const std::string &ns="")
void processInteractiveMarkerFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
static std::string getMarkerName(const ::robot_interaction::InteractionHandlerPtr &handler, const EndEffectorInteraction &eef)
boost::function< bool(const robot_state::RobotState &state, visualization_msgs::InteractiveMarker &marker)> InteractiveMarkerConstructorFn
bool run_processing_thread_
void add6DOFControl(visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
void computeMarkerPose(const ::robot_interaction::InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, const robot_state::RobotState &robot_state, geometry_msgs::Pose &pose, geometry_msgs::Pose &control_to_eef_tf) const
std::string marker_name_suffix
std::string connecting_link
The link in the robot model this joint is a parent of.
std::string parent_frame
The name of the frame that is a parent of this joint.
unsigned int dof
The type of joint disguised as the number of DOF it has. 3=PLANAR in X/Y; 6=FLOATING.
INTERACTIVE_MARKERS_PUBLIC void insert(const visualization_msgs::InteractiveMarker &int_marker)
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
INTERACTIVE_MARKERS_PUBLIC void applyChanges()
INTERACTIVE_MARKERS_PUBLIC bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
void addInteractiveMarkers(const ::robot_interaction::InteractionHandlerPtr &handler, const double marker_scale=0.0)
boost::mutex marker_access_lock_
InteractiveMarkerConstructorFn construct_marker
std::vector< EndEffectorInteraction > active_eef_
INTERACTIVE_MARKERS_PUBLIC void clear()
bool showingMarkers(const ::robot_interaction::InteractionHandlerPtr &handler)
INTERACTIVE_MARKERS_PUBLIC bool setPose(const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header=std_msgs::Header())
std::unique_ptr< boost::thread > processing_thread_
std::string joint_name
The name of the joint.
std::map< std::string, std::size_t > shown_markers_
std::vector< GenericInteraction > active_generic_
void updateInteractiveMarkers(const ::robot_interaction::InteractionHandlerPtr &handler)
ProcessFeedbackFn process_feedback
InteractiveMarkerUpdateFn update_pose
void addActiveComponent(const InteractiveMarkerConstructorFn &construct, const ProcessFeedbackFn &process, const InteractiveMarkerUpdateFn &update=InteractiveMarkerUpdateFn(), const std::string &name="")
static const std::string INTERACTIVE_MARKER_TOPIC
The topic name on which the internal Interactive Marker Server operates.
void decideActiveComponents(const std::string &group)
void publishInteractiveMarkers()