moveit2
The MoveIt Motion Planning Framework for ROS 2.
robot_interaction.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Adam Leeper */
36 
37 #pragma once
38 
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 <memory>
46 #include <functional>
47 #include <thread>
48 
49 // This is needed for legacy code that includes robot_interaction.h but not
50 // interaction_handler.h
52 
54 {
55 class InteractiveMarkerServer;
56 }
57 
58 namespace robot_interaction
59 {
60 MOVEIT_CLASS_FORWARD(InteractionHandler); // Defines InteractionHandlerPtr, ConstPtr, WeakPtr... etc
61 MOVEIT_CLASS_FORWARD(KinematicOptionsMap); // Defines KinematicOptionsMapPtr, ConstPtr, WeakPtr... etc
62 MOVEIT_CLASS_FORWARD(RobotInteraction); // Defines RobotInteractionPtr, ConstPtr, WeakPtr... etc
63 
64 // Manage interactive markers for controlling a robot state.
65 //
66 // The RobotInteraction class manages one or more InteractionHandler objects
67 // each of which maintains a set of interactive markers for manipulating one
68 // group of one RobotState.
69 //
70 // The group being manipulated is common to all InteractionHandler objects
71 // contained in a RobotInteraction instance.
73 {
74 public:
76  static const std::string INTERACTIVE_MARKER_TOPIC;
77 
78  RobotInteraction(const moveit::core::RobotModelConstPtr& robot_model, const rclcpp::Node::SharedPtr& node,
79  const std::string& ns = "");
80  virtual ~RobotInteraction();
81 
82  const std::string& getServerTopic() const
83  {
84  return topic_;
85  }
86 
98  void addActiveComponent(const InteractiveMarkerConstructorFn& construct, const ProcessFeedbackFn& process,
100  const std::string& name = "");
101 
110  void decideActiveComponents(const std::string& group);
111  void decideActiveComponents(const std::string& group, InteractionStyle::InteractionStyle style);
112 
115  void clear();
116 
122  void addInteractiveMarkers(const InteractionHandlerPtr& handler, const double marker_scale = 0.0);
123 
124  // Update pose of all interactive markers to match the handler's RobotState.
125  // Call this when the handler's RobotState changes.
126  void updateInteractiveMarkers(const InteractionHandlerPtr& handler);
127 
128  // True if markers are being shown for this handler.
129  bool showingMarkers(const InteractionHandlerPtr& handler);
130 
131  // Display all markers that have been added.
132  // This is needed after calls to addInteractiveMarkers() to publish the
133  // resulting markers so they get displayed. This call is not needed after
134  // calling updateInteractiveMarkers() which publishes the results itself.
136 
137  // Clear all interactive markers.
138  // This removes all interactive markers but does not affect which
139  // interactions are active. After this a call to publishInteractiveMarkers()
140  // is needed to actually remove the markers from the display.
142 
143  const moveit::core::RobotModelConstPtr& getRobotModel() const
144  {
145  return robot_model_;
146  }
147 
148  // Get the kinematic options map.
149  // Use this to set kinematic options (defaults or per-group).
150  KinematicOptionsMapPtr getKinematicOptionsMap()
151  {
152  return kinematic_options_map_;
153  }
154 
155  // enable/disable subscription of the topics to move interactive marker
156  void toggleMoveInteractiveMarkerTopic(bool enable);
157 
158  const std::vector<EndEffectorInteraction>& getActiveEndEffectors() const
159  {
160  return active_eef_;
161  }
162  const std::vector<JointInteraction>& getActiveJoints() const
163  {
164  return active_vj_;
165  }
166 
167 private:
168  // called by decideActiveComponents(); add markers for end effectors
169  void decideActiveEndEffectors(const std::string& group);
170  void decideActiveEndEffectors(const std::string& group, InteractionStyle::InteractionStyle style);
171 
172  // called by decideActiveComponents(); add markers for planar and floating joints
173  void decideActiveJoints(const std::string& group);
174 
175  void moveInteractiveMarker(const std::string& name, const geometry_msgs::msg::PoseStamped& msg);
176  // register the name of the topic and marker name to move interactive marker from other ROS nodes
177  void registerMoveInteractiveMarkerTopic(const std::string& marker_name, const std::string& name);
178  // return the diameter of the sphere that certainly can enclose the AABB of the link
179  double computeLinkMarkerSize(const std::string& link);
180  // return the diameter of the sphere that certainly can enclose the AABB of the links in this group
181  double computeGroupMarkerSize(const std::string& group);
182  void computeMarkerPose(const InteractionHandlerPtr& handler, const EndEffectorInteraction& eef,
183  const moveit::core::RobotState& robot_state, geometry_msgs::msg::Pose& pose,
184  geometry_msgs::msg::Pose& control_to_eef_tf) const;
185 
186  void addEndEffectorMarkers(const InteractionHandlerPtr& handler, const EndEffectorInteraction& eef,
187  visualization_msgs::msg::InteractiveMarker& im, bool position = true,
188  bool orientation = true);
189  void addEndEffectorMarkers(const InteractionHandlerPtr& handler, const EndEffectorInteraction& eef,
190  const geometry_msgs::msg::Pose& offset, visualization_msgs::msg::InteractiveMarker& im,
191  bool position = true, bool orientation = true);
192 
193  void
194  processInteractiveMarkerFeedback(const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback);
195  void subscribeMoveInteractiveMarker(const std::string marker_name, const std::string& name);
196  void processingThread();
197  void clearInteractiveMarkersUnsafe();
198 
199  std::unique_ptr<std::thread> processing_thread_;
200  bool run_processing_thread_;
201 
202  std::condition_variable new_feedback_condition_;
203  std::map<std::string, visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr> feedback_map_;
204 
205  moveit::core::RobotModelConstPtr robot_model_;
206 
207  std::vector<EndEffectorInteraction> active_eef_;
208  std::vector<JointInteraction> active_vj_;
209  std::vector<GenericInteraction> active_generic_;
210 
211  std::map<std::string, InteractionHandlerPtr> handlers_;
212  std::map<std::string, std::size_t> shown_markers_;
213 
214  // This mutex is locked every time markers are read or updated;
215  // This includes the active_* arrays and shown_markers_
216  // Please note that this mutex *MUST NOT* be locked while operations
217  // on the interactive marker server are called because the server
218  // also locks internally and we could othewrise end up with a problem
219  // of Thread 1: Lock A, Lock B, Unlock B, Unloack A
220  // Thread 2: Lock B, Lock A
221  // => deadlock
222  std::mutex marker_access_lock_;
223 
224  interactive_markers::InteractiveMarkerServer* int_marker_server_;
225  // ros subscribers to move the interactive markers by other ros nodes
226  std::vector<rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr> int_marker_move_subscribers_;
227  // the array of the names of the topics which need to be subscribed
228  // to move the interactive markers by other ROS nodes
229  std::vector<std::string> int_marker_move_topics_;
230  // the array of the marker names in the same order to int_marker_move_topics_
231  std::vector<std::string> int_marker_names_;
232 
233  std::string topic_;
234  rclcpp::Node::SharedPtr node_;
235 
236  // options for doing IK
237  KinematicOptionsMapPtr kinematic_options_map_;
238 };
239 } // namespace robot_interaction
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void updateInteractiveMarkers(const InteractionHandlerPtr &handler)
void decideActiveComponents(const std::string &group)
KinematicOptionsMapPtr getKinematicOptionsMap()
const std::vector< EndEffectorInteraction > & getActiveEndEffectors() const
const std::vector< JointInteraction > & getActiveJoints() const
const std::string & getServerTopic() const
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.
MOVEIT_CLASS_FORWARD(InteractionHandler)
std::function< bool(moveit::core::RobotState &state, const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr &feedback)> ProcessFeedbackFn
Definition: interaction.h:103
std::function< bool(const moveit::core::RobotState &, geometry_msgs::msg::Pose &)> InteractiveMarkerUpdateFn
Definition: interaction.h:114
std::function< bool(const moveit::core::RobotState &state, visualization_msgs::msg::InteractiveMarker &marker)> InteractiveMarkerConstructorFn
Definition: interaction.h:88
name
Definition: setup.py:7