39 #include <visualization_msgs/msg/interactive_marker_feedback.hpp>
40 #include <visualization_msgs/msg/interactive_marker.hpp>
41 #include <interactive_markers/menu_handler.hpp>
45 #include <rclcpp/logger.hpp>
56 class InteractiveMarkerServer;
79 RobotInteraction(
const moveit::core::RobotModelConstPtr& robot_model,
const rclcpp::Node::SharedPtr& node,
80 const std::string& ns =
"");
101 const std::string&
name =
"");
153 return kinematic_options_map_;
170 void decideActiveEndEffectors(
const std::string& group);
174 void decideActiveJoints(
const std::string& group);
176 void moveInteractiveMarker(
const std::string&
name,
const geometry_msgs::msg::PoseStamped& msg);
178 void registerMoveInteractiveMarkerTopic(
const std::string& marker_name,
const std::string&
name);
180 double computeLinkMarkerSize(
const std::string& link);
182 double computeGroupMarkerSize(
const std::string& group);
185 geometry_msgs::msg::Pose& control_to_eef_tf)
const;
188 visualization_msgs::msg::InteractiveMarker& im,
bool position =
true,
189 bool orientation =
true);
191 const geometry_msgs::msg::Pose& offset, visualization_msgs::msg::InteractiveMarker& im,
192 bool position =
true,
bool orientation =
true);
195 processInteractiveMarkerFeedback(
const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback);
196 void subscribeMoveInteractiveMarker(
const std::string marker_name,
const std::string&
name);
197 void processingThread();
198 void clearInteractiveMarkersUnsafe();
200 std::unique_ptr<std::thread> processing_thread_;
201 bool run_processing_thread_;
203 std::condition_variable new_feedback_condition_;
204 std::map<std::string, visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr> feedback_map_;
206 moveit::core::RobotModelConstPtr robot_model_;
208 std::vector<EndEffectorInteraction> active_eef_;
209 std::vector<JointInteraction> active_vj_;
210 std::vector<GenericInteraction> active_generic_;
212 std::map<std::string, InteractionHandlerPtr> handlers_;
213 std::map<std::string, std::size_t> shown_markers_;
223 std::mutex marker_access_lock_;
225 interactive_markers::InteractiveMarkerServer* int_marker_server_;
227 std::vector<rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr> int_marker_move_subscribers_;
230 std::vector<std::string> int_marker_move_topics_;
232 std::vector<std::string> int_marker_names_;
235 rclcpp::Node::SharedPtr node_;
236 rclcpp::Logger logger_;
239 KinematicOptionsMapPtr kinematic_options_map_;
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void publishInteractiveMarkers()
void clearInteractiveMarkers()
void updateInteractiveMarkers(const InteractionHandlerPtr &handler)
void decideActiveComponents(const std::string &group)
void toggleMoveInteractiveMarkerTopic(bool enable)
KinematicOptionsMapPtr getKinematicOptionsMap()
const std::vector< EndEffectorInteraction > & getActiveEndEffectors() const
const std::vector< JointInteraction > & getActiveJoints() const
const std::string & getServerTopic() const
virtual ~RobotInteraction()
RobotInteraction(const moveit::core::RobotModelConstPtr &robot_model, const rclcpp::Node::SharedPtr &node, const std::string &ns="")
bool showingMarkers(const InteractionHandlerPtr &handler)
void addActiveComponent(const InteractiveMarkerConstructorFn &construct, const ProcessFeedbackFn &process, const InteractiveMarkerUpdateFn &update=InteractiveMarkerUpdateFn(), const std::string &name="")
void addInteractiveMarkers(const InteractionHandlerPtr &handler, const double marker_scale=0.0)
const moveit::core::RobotModelConstPtr & getRobotModel() const
static const std::string INTERACTIVE_MARKER_TOPIC
The topic name on which the internal Interactive Marker Server operates.
void update(moveit::core::RobotState *self, bool force, std::string &category)
MOVEIT_CLASS_FORWARD(InteractionHandler)
std::function< bool(moveit::core::RobotState &state, const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr &feedback)> ProcessFeedbackFn
std::function< bool(const moveit::core::RobotState &, geometry_msgs::msg::Pose &)> InteractiveMarkerUpdateFn
std::function< bool(const moveit::core::RobotState &state, visualization_msgs::msg::InteractiveMarker &marker)> InteractiveMarkerConstructorFn