37 #ifndef MOVEIT_ROBOT_INTERACTION_ROBOT_INTERACTION_ 38 #define MOVEIT_ROBOT_INTERACTION_ROBOT_INTERACTION_ 40 #include <visualization_msgs/InteractiveMarkerFeedback.h> 41 #include <visualization_msgs/InteractiveMarker.h> 42 #include <geometry_msgs/PoseArray.h> 47 #include <boost/function.hpp> 48 #include <boost/thread.hpp> 57 class InteractiveMarkerServer;
80 typedef ::robot_interaction::EndEffectorInteraction
EndEffector;
81 typedef ::robot_interaction::JointInteraction
Joint;
82 typedef ::robot_interaction::GenericInteraction
Generic;
88 RobotInteraction(
const robot_model::RobotModelConstPtr& kmodel,
const std::string& ns =
"");
109 const std::string& name =
"");
119 void decideActiveComponents(
const std::string& group);
131 void addInteractiveMarkers(const ::robot_interaction::InteractionHandlerPtr& handler,
132 const double marker_scale = 0.0);
136 void updateInteractiveMarkers(const ::robot_interaction::InteractionHandlerPtr& handler);
139 bool showingMarkers(const ::robot_interaction::InteractionHandlerPtr& handler);
145 void publishInteractiveMarkers();
151 void clearInteractiveMarkers();
162 return kinematic_options_map_;
166 void toggleMoveInteractiveMarkerTopic(
bool enable);
170 void decideActiveEndEffectors(
const std::string& group);
175 void decideActiveJoints(
const std::string& group);
177 void moveInteractiveMarker(
const std::string name,
const geometry_msgs::PoseStampedConstPtr& msg);
180 void registerMoveInteractiveMarkerTopic(
const std::string marker_name,
const std::string& name);
182 double computeLinkMarkerSize(
const std::string& link);
185 double computeGroupMarkerSize(
const std::string& group);
186 void computeMarkerPose(const ::robot_interaction::InteractionHandlerPtr& handler,
const EndEffectorInteraction& eef,
187 const robot_state::RobotState& robot_state, geometry_msgs::Pose& pose,
188 geometry_msgs::Pose& control_to_eef_tf)
const;
190 void addEndEffectorMarkers(const ::robot_interaction::InteractionHandlerPtr& handler,
192 bool position =
true,
bool orientation =
true);
193 void addEndEffectorMarkers(const ::robot_interaction::InteractionHandlerPtr& handler,
195 visualization_msgs::InteractiveMarker& im,
bool position =
true,
bool orientation =
true);
196 void processInteractiveMarkerFeedback(
const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
197 void subscribeMoveInteractiveMarker(
const std::string marker_name,
const std::string& name);
198 void processingThread();
199 void clearInteractiveMarkersUnsafe();
205 std::map<std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr>
feedback_map_;
213 std::map<std::string, ::robot_interaction::InteractionHandlerPtr>
handlers_;
280 static bool updateState(
282 unsigned int attempts,
double ik_timeout,
283 const robot_state::GroupStateValidityCallbackFn& validity_callback = robot_state::GroupStateValidityCallbackFn(),
boost::condition_variable new_feedback_condition_
::robot_interaction::GenericInteraction Generic
std::vector< JointInteraction > active_vj_
::robot_interaction::InteractionHandlerPtr InteractionHandlerPtr
const std::vector< EndEffectorInteraction > & getActiveEndEffectors() const
std::map< std::string,::robot_interaction::InteractionHandlerPtr > handlers_
::robot_interaction::JointInteraction Joint
const std::string & getServerTopic(void) const
KinematicOptionsMapPtr getKinematicOptionsMap()
const std::vector< JointInteraction > & getActiveJoints() const
EndEffectorInteractionStyle
const robot_model::RobotModelConstPtr & getRobotModel() const
std::vector< ros::Subscriber > int_marker_move_subscribers_
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::vector< std::string > int_marker_names_
interactive_markers::InteractiveMarkerServer * int_marker_server_
robot_model::RobotModelConstPtr robot_model_
KinematicOptionsMapPtr kinematic_options_map_
std::vector< std::string > int_marker_move_topics_
std::map< std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr > feedback_map_
boost::function< bool(const robot_state::RobotState &, geometry_msgs::Pose &)> InteractiveMarkerUpdateFn
boost::function< bool(robot_state::RobotState &state, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)> ProcessFeedbackFn
boost::function< bool(const robot_state::RobotState &state, visualization_msgs::InteractiveMarker &marker)> InteractiveMarkerConstructorFn
bool run_processing_thread_
::robot_interaction::InteractionHandler InteractionHandler
boost::mutex marker_access_lock_
std::vector< EndEffectorInteraction > active_eef_
::robot_interaction::EndEffectorInteraction EndEffector
std::unique_ptr< boost::thread > processing_thread_
std::map< std::string, std::size_t > shown_markers_
std::vector< GenericInteraction > active_generic_
static const std::string INTERACTIVE_MARKER_TOPIC
The topic name on which the internal Interactive Marker Server operates.
MOVEIT_CLASS_FORWARD(InteractionHandler)