moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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 <rclcpp/logger.hpp>
46#include <memory>
47#include <functional>
48#include <thread>
49
50// This is needed for legacy code that includes robot_interaction.h but not
51// interaction_handler.h
53
55{
56class InteractiveMarkerServer;
57}
58
59namespace robot_interaction
60{
61MOVEIT_CLASS_FORWARD(InteractionHandler); // Defines InteractionHandlerPtr, ConstPtr, WeakPtr... etc
62MOVEIT_CLASS_FORWARD(KinematicOptionsMap); // Defines KinematicOptionsMapPtr, ConstPtr, WeakPtr... etc
63MOVEIT_CLASS_FORWARD(RobotInteraction); // Defines RobotInteractionPtr, ConstPtr, WeakPtr... etc
64
65// Manage interactive markers for controlling a robot state.
66//
67// The RobotInteraction class manages one or more InteractionHandler objects
68// each of which maintains a set of interactive markers for manipulating one
69// group of one RobotState.
70//
71// The group being manipulated is common to all InteractionHandler objects
72// contained in a RobotInteraction instance.
74{
75public:
77 static const std::string INTERACTIVE_MARKER_TOPIC;
78
79 RobotInteraction(const moveit::core::RobotModelConstPtr& robot_model, const rclcpp::Node::SharedPtr& node,
80 const std::string& ns = "");
81 virtual ~RobotInteraction();
82
83 const std::string& getServerTopic() const
84 {
85 return topic_;
86 }
87
99 void addActiveComponent(const InteractiveMarkerConstructorFn& construct, const ProcessFeedbackFn& process,
101 const std::string& name = "");
102
111 void decideActiveComponents(const std::string& group);
112 void decideActiveComponents(const std::string& group, InteractionStyle::InteractionStyle style);
113
116 void clear();
117
123 void addInteractiveMarkers(const InteractionHandlerPtr& handler, const double marker_scale = 0.0);
124
125 // Update pose of all interactive markers to match the handler's RobotState.
126 // Call this when the handler's RobotState changes.
127 void updateInteractiveMarkers(const InteractionHandlerPtr& handler);
128
129 // True if markers are being shown for this handler.
130 bool showingMarkers(const InteractionHandlerPtr& handler);
131
132 // Display all markers that have been added.
133 // This is needed after calls to addInteractiveMarkers() to publish the
134 // resulting markers so they get displayed. This call is not needed after
135 // calling updateInteractiveMarkers() which publishes the results itself.
137
138 // Clear all interactive markers.
139 // This removes all interactive markers but does not affect which
140 // interactions are active. After this a call to publishInteractiveMarkers()
141 // is needed to actually remove the markers from the display.
143
144 const moveit::core::RobotModelConstPtr& getRobotModel() const
145 {
146 return robot_model_;
147 }
148
149 // Get the kinematic options map.
150 // Use this to set kinematic options (defaults or per-group).
151 KinematicOptionsMapPtr getKinematicOptionsMap()
152 {
153 return kinematic_options_map_;
154 }
155
156 // enable/disable subscription of the topics to move interactive marker
157 void toggleMoveInteractiveMarkerTopic(bool enable);
158
159 const std::vector<EndEffectorInteraction>& getActiveEndEffectors() const
160 {
161 return active_eef_;
162 }
163 const std::vector<JointInteraction>& getActiveJoints() const
164 {
165 return active_vj_;
166 }
167
168private:
169 // called by decideActiveComponents(); add markers for end effectors
170 void decideActiveEndEffectors(const std::string& group);
171 void decideActiveEndEffectors(const std::string& group, InteractionStyle::InteractionStyle style);
172
173 // called by decideActiveComponents(); add markers for planar and floating joints
174 void decideActiveJoints(const std::string& group);
175
176 void moveInteractiveMarker(const std::string& name, const geometry_msgs::msg::PoseStamped& msg);
177 // register the name of the topic and marker name to move interactive marker from other ROS nodes
178 void registerMoveInteractiveMarkerTopic(const std::string& marker_name, const std::string& name);
179 // return the diameter of the sphere that certainly can enclose the AABB of the link
180 double computeLinkMarkerSize(const std::string& link);
181 // return the diameter of the sphere that certainly can enclose the AABB of the links in this group
182 double computeGroupMarkerSize(const std::string& group);
183 void computeMarkerPose(const InteractionHandlerPtr& handler, const EndEffectorInteraction& eef,
184 const moveit::core::RobotState& robot_state, geometry_msgs::msg::Pose& pose,
185 geometry_msgs::msg::Pose& control_to_eef_tf) const;
186
187 void addEndEffectorMarkers(const InteractionHandlerPtr& handler, const EndEffectorInteraction& eef,
188 visualization_msgs::msg::InteractiveMarker& im, bool position = true,
189 bool orientation = true);
190 void addEndEffectorMarkers(const InteractionHandlerPtr& handler, const EndEffectorInteraction& eef,
191 const geometry_msgs::msg::Pose& offset, visualization_msgs::msg::InteractiveMarker& im,
192 bool position = true, bool orientation = true);
193
194 void
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();
199
200 std::unique_ptr<std::thread> processing_thread_;
201 bool run_processing_thread_;
202
203 std::condition_variable new_feedback_condition_;
204 std::map<std::string, visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr> feedback_map_;
205
206 moveit::core::RobotModelConstPtr robot_model_;
207
208 std::vector<EndEffectorInteraction> active_eef_;
209 std::vector<JointInteraction> active_vj_;
210 std::vector<GenericInteraction> active_generic_;
211
212 std::map<std::string, InteractionHandlerPtr> handlers_;
213 std::map<std::string, std::size_t> shown_markers_;
214
215 // This mutex is locked every time markers are read or updated;
216 // This includes the active_* arrays and shown_markers_
217 // Please note that this mutex *MUST NOT* be locked while operations
218 // on the interactive marker server are called because the server
219 // also locks internally and we could othewrise end up with a problem
220 // of Thread 1: Lock A, Lock B, Unlock B, Unloack A
221 // Thread 2: Lock B, Lock A
222 // => deadlock
223 std::mutex marker_access_lock_;
224
225 interactive_markers::InteractiveMarkerServer* int_marker_server_;
226 // ros subscribers to move the interactive markers by other ros nodes
227 std::vector<rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr> int_marker_move_subscribers_;
228 // the array of the names of the topics which need to be subscribed
229 // to move the interactive markers by other ROS nodes
230 std::vector<std::string> int_marker_move_topics_;
231 // the array of the marker names in the same order to int_marker_move_topics_
232 std::vector<std::string> int_marker_names_;
233
234 std::string topic_;
235 rclcpp::Node::SharedPtr node_;
236 rclcpp::Logger logger_;
237
238 // options for doing IK
239 KinematicOptionsMapPtr kinematic_options_map_;
240};
241} // namespace robot_interaction
#define MOVEIT_CLASS_FORWARD(C)
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)
const std::string & getServerTopic() const
KinematicOptionsMapPtr getKinematicOptionsMap()
const std::vector< JointInteraction > & getActiveJoints() const
bool showingMarkers(const InteractionHandlerPtr &handler)
const moveit::core::RobotModelConstPtr & getRobotModel() const
void addActiveComponent(const InteractiveMarkerConstructorFn &construct, const ProcessFeedbackFn &process, const InteractiveMarkerUpdateFn &update=InteractiveMarkerUpdateFn(), const std::string &name="")
const std::vector< EndEffectorInteraction > & getActiveEndEffectors() const
void addInteractiveMarkers(const InteractionHandlerPtr &handler, const double marker_scale=0.0)
static const std::string INTERACTIVE_MARKER_TOPIC
The topic name on which the internal Interactive Marker Server operates.
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
Definition interaction.h:88