Go to the documentation of this file.
39 #include <visualization_msgs/InteractiveMarkerFeedback.h>
40 #include <visualization_msgs/InteractiveMarker.h>
45 #include <boost/function.hpp>
46 #include <boost/thread.hpp>
55 class InteractiveMarkerServer;
78 RobotInteraction(
const moveit::core::RobotModelConstPtr& robot_model,
const std::string& ns =
"");
99 const std::string& name =
"");
183 geometry_msgs::Pose& control_to_eef_tf)
const;
186 visualization_msgs::InteractiveMarker& im,
bool position =
true,
bool orientation =
true);
188 const geometry_msgs::Pose& offset, visualization_msgs::InteractiveMarker& im,
189 bool position =
true,
bool orientation =
true);
199 std::map<std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr>
feedback_map_;
void toggleMoveInteractiveMarkerTopic(bool enable)
static const std::string INTERACTIVE_MARKER_TOPIC
The topic name on which the internal Interactive Marker Server operates.
void decideActiveEndEffectors(const std::string &group)
RobotInteraction(const moveit::core::RobotModelConstPtr &robot_model, const std::string &ns="")
void registerMoveInteractiveMarkerTopic(const std::string &marker_name, const std::string &name)
KinematicOptionsMapPtr getKinematicOptionsMap()
std::vector< ros::Subscriber > int_marker_move_subscribers_
void processInteractiveMarkerFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
boost::mutex marker_access_lock_
void decideActiveComponents(const std::string &group)
std::map< std::string, InteractionHandlerPtr > handlers_
std::map< std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr > feedback_map_
void decideActiveJoints(const std::string &group)
void updateInteractiveMarkers(const InteractionHandlerPtr &handler)
boost::function< bool(const moveit::core::RobotState &, geometry_msgs::Pose &)> InteractiveMarkerUpdateFn
boost::function< bool(const moveit::core::RobotState &state, visualization_msgs::InteractiveMarker &marker)> InteractiveMarkerConstructorFn
void computeMarkerPose(const InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, const moveit::core::RobotState &robot_state, geometry_msgs::Pose &pose, geometry_msgs::Pose &control_to_eef_tf) const
void addActiveComponent(const InteractiveMarkerConstructorFn &construct, const ProcessFeedbackFn &process, const InteractiveMarkerUpdateFn &update=InteractiveMarkerUpdateFn(), const std::string &name="")
std::vector< GenericInteraction > active_generic_
const std::vector< JointInteraction > & getActiveJoints() const
interactive_markers::InteractiveMarkerServer * int_marker_server_
const moveit::core::RobotModelConstPtr & getRobotModel() const
bool showingMarkers(const InteractionHandlerPtr &handler)
std::vector< std::string > int_marker_names_
MOVEIT_CLASS_FORWARD(InteractionHandler)
std::unique_ptr< boost::thread > processing_thread_
const std::vector< EndEffectorInteraction > & getActiveEndEffectors() const
bool run_processing_thread_
moveit::core::RobotModelConstPtr robot_model_
void clearInteractiveMarkersUnsafe()
const std::string & getServerTopic() const
void clearInteractiveMarkers()
std::vector< std::string > int_marker_move_topics_
void publishInteractiveMarkers()
double computeLinkMarkerSize(const std::string &link)
boost::function< bool(moveit::core::RobotState &state, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)> ProcessFeedbackFn
std::vector< EndEffectorInteraction > active_eef_
void addEndEffectorMarkers(const InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, visualization_msgs::InteractiveMarker &im, bool position=true, bool orientation=true)
KinematicOptionsMapPtr kinematic_options_map_
void subscribeMoveInteractiveMarker(const std::string marker_name, const std::string &name)
double computeGroupMarkerSize(const std::string &group)
std::map< std::string, std::size_t > shown_markers_
boost::condition_variable new_feedback_condition_
void moveInteractiveMarker(const std::string &name, const geometry_msgs::PoseStamped &msg)
virtual ~RobotInteraction()
void addInteractiveMarkers(const InteractionHandlerPtr &handler, const double marker_scale=0.0)
std::vector< JointInteraction > active_vj_