moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
interaction_handler.hpp
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 <rclcpp/version.h>
40#include <geometry_msgs/msg/pose_stamped.hpp>
43#include <visualization_msgs/msg/interactive_marker_feedback.hpp>
44#include <interactive_markers/menu_handler.hpp>
45// For Rolling, Kilted, and newer
46#if RCLCPP_VERSION_GTE(29, 6, 0)
47#include <tf2_ros/buffer.hpp>
48// For Jazzy and older
49#else
50#include <tf2_ros/buffer.h>
51#endif
52
53namespace robot_interaction
54{
55MOVEIT_CLASS_FORWARD(InteractionHandler); // Defines InteractionHandlerPtr, ConstPtr, WeakPtr... etc
56MOVEIT_CLASS_FORWARD(RobotInteraction); // Defines RobotInteractionPtr, ConstPtr, WeakPtr... etc
57MOVEIT_CLASS_FORWARD(KinematicOptionsMap); // Defines KinematicOptionsMapPtr, ConstPtr, WeakPtr... etc
58
60struct JointInteraction;
62
72typedef std::function<void(InteractionHandler*, bool)> InteractionHandlerCallbackFn;
73
83{
84public:
85 // Use this constructor if you have an initial RobotState already.
86 InteractionHandler(const RobotInteractionPtr& robot_interaction, const std::string& name,
87 const moveit::core::RobotState& initial_robot_state,
88 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>());
89
90 // Use this constructor to start with a default state.
91 InteractionHandler(const RobotInteractionPtr& robot_interaction, const std::string& name,
92 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>());
93
94 // DEPRECATED.
95 InteractionHandler(const std::string& name, const moveit::core::RobotState& initial_robot_state,
96 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>());
97 // DEPRECATED.
98 InteractionHandler(const std::string& name, const moveit::core::RobotModelConstPtr& model,
99 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>());
100
102 {
103 }
104
105 const std::string& getName() const
106 {
107 return name_;
108 }
109
112
115
118 void setMeshesVisible(bool visible);
119 bool getMeshesVisible() const;
120 void setControlsVisible(bool visible);
121 bool getControlsVisible() const;
122
126 void setPoseOffset(const EndEffectorInteraction& eef, const geometry_msgs::msg::Pose& m);
127
131 void setPoseOffset(const JointInteraction& j, const geometry_msgs::msg::Pose& m);
132
137 bool getPoseOffset(const EndEffectorInteraction& eef, geometry_msgs::msg::Pose& m);
138
143 bool getPoseOffset(const JointInteraction& vj, geometry_msgs::msg::Pose& m);
144
149
152 void clearPoseOffset(const JointInteraction& vj);
153
155 void clearPoseOffsets();
156
160 void setMenuHandler(const std::shared_ptr<interactive_markers::MenuHandler>& mh);
161
165 const std::shared_ptr<interactive_markers::MenuHandler>& getMenuHandler();
166
168 void clearMenuHandler();
169
175 bool getLastEndEffectorMarkerPose(const EndEffectorInteraction& eef, geometry_msgs::msg::PoseStamped& pose);
176
182 bool getLastJointMarkerPose(const JointInteraction& vj, geometry_msgs::msg::PoseStamped& pose);
183
188
192
196
199 virtual void handleEndEffector(const EndEffectorInteraction& eef,
200 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback);
201
204 virtual void handleJoint(const JointInteraction& vj,
205 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback);
206
209 virtual void handleGeneric(const GenericInteraction& g,
210 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback);
211
214 virtual bool inError(const EndEffectorInteraction& eef) const;
215
218 virtual bool inError(const JointInteraction& vj) const;
219
221 virtual bool inError(const GenericInteraction& g) const;
222
225 void clearError();
226
227protected:
228 bool transformFeedbackPose(const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback,
229 const geometry_msgs::msg::Pose& offset, geometry_msgs::msg::PoseStamped& tpose);
230
231 const std::string name_;
232 const std::string planning_frame_;
233 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
234
235private:
236 typedef std::function<void(InteractionHandler*)> StateChangeCallbackFn;
237
238 // Update RobotState using a generic interaction feedback message.
239 // YOU MUST LOCK state_lock_ BEFORE CALLING THIS.
240 void updateStateGeneric(moveit::core::RobotState& state, const GenericInteraction& g,
241 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback,
242 StateChangeCallbackFn& callback);
243
244 // Update RobotState for a new pose of an eef.
245 // YOU MUST LOCK state_lock_ BEFORE CALLING THIS.
246 void updateStateEndEffector(moveit::core::RobotState& state, const EndEffectorInteraction& eef,
247 const geometry_msgs::msg::Pose& pose, StateChangeCallbackFn& callback);
248
249 // Update RobotState for a new joint position.
250 // YOU MUST LOCK state_lock_ BEFORE CALLING THIS.
251 void updateStateJoint(moveit::core::RobotState& state, const JointInteraction& vj,
252 const geometry_msgs::msg::Pose& pose, StateChangeCallbackFn& callback);
253
254 // Set the error state for \e name.
255 // Returns true if the error state for \e name changed.
256 // YOU MUST LOCK state_lock_ BEFORE CALLING THIS.
257 bool setErrorState(const std::string& name, bool new_error_state);
258
261 bool getErrorState(const std::string& name) const;
262
263 // Contains the (user-programmable) pose offset between the end-effector
264 // parent link (or a virtual joint) and the desired control frame for the
265 // interactive marker. The offset is expressed in the frame of the parent
266 // link or virtual joint. For example, on a PR2 an offset of +0.20 along
267 // the x-axis will move the center of the 6-DOF interactive marker from
268 // the wrist to the finger tips.
269 // PROTECTED BY offset_map_lock_
270 std::map<std::string, geometry_msgs::msg::Pose> offset_map_;
271
272 // Contains the most recent poses received from interactive marker feedback,
273 // with the offset removed (e.g. in theory, coinciding with the end-effector
274 // parent or virtual joint). This allows a user application to query for the
275 // interactive marker pose (which could be useful for robot control using
276 // gradient-based methods) even when the IK solver failed to find a valid
277 // robot state that satisfies the feedback pose.
278 // PROTECTED BY pose_map_lock_
279 std::map<std::string, geometry_msgs::msg::PoseStamped> pose_map_;
280
281 std::mutex pose_map_lock_;
282 std::mutex offset_map_lock_;
283
284 // per group options for doing kinematics.
285 // PROTECTED BY state_lock_ - The POINTER is protected by state_lock_. The
286 // CONTENTS is protected internally.
287 KinematicOptionsMapPtr kinematic_options_map_;
288
289 // A set of Interactions for which the pose is invalid.
290 // PROTECTED BY state_lock_
291 std::set<std::string> error_state_;
292
293 // For adding menus (and associated callbacks) to all the
294 // end-effector and virtual-joint interactive markers
295 //
296 // PROTECTED BY state_lock_ - The POINTER is protected by state_lock_. The
297 // CONTENTS is not.
298 std::shared_ptr<interactive_markers::MenuHandler> menu_handler_;
299
300 // Called when the RobotState maintained by the handler changes.
301 // The caller may, for example, redraw the robot at the new state.
302 // handler is the handler that changed.
303 // error_state_changed is true if an end effector's error state may have
304 // changed.
305 //
306 // PROTECTED BY state_lock_ - the function pointer is protected, but the call
307 // is made without any lock held.
308 std::function<void(InteractionHandler* handler, bool error_state_changed)> update_callback_;
309
310 // PROTECTED BY state_lock_
311 bool display_meshes_;
312
313 // PROTECTED BY state_lock_
314 bool display_controls_;
315
316 // remove '_' characters from name
317 static std::string fixName(std::string name);
318};
319} // namespace robot_interaction
#define MOVEIT_CLASS_FORWARD(C)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void clearPoseOffset(const EndEffectorInteraction &eef)
Clear the interactive marker pose offset for the given end-effector.
bool getLastJointMarkerPose(const JointInteraction &vj, geometry_msgs::msg::PoseStamped &pose)
Get the last interactive_marker command pose for a joint.
void clearPoseOffsets()
Clear the pose offset for all end-effectors and virtual joints.
InteractionHandler(const std::string &name, const moveit::core::RobotState &initial_robot_state, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer=std::shared_ptr< tf2_ros::Buffer >())
const std::shared_ptr< interactive_markers::MenuHandler > & getMenuHandler()
Get the menu handler that defines menus and callbacks for all interactive markers drawn by this inter...
virtual void handleGeneric(const GenericInteraction &g, const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr &feedback)
Update the internal state maintained by the handler using information from the received feedback mess...
void setUpdateCallback(const InteractionHandlerCallbackFn &callback)
bool getLastEndEffectorMarkerPose(const EndEffectorInteraction &eef, geometry_msgs::msg::PoseStamped &pose)
Get the last interactive_marker command pose for an end-effector.
virtual void handleJoint(const JointInteraction &vj, const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr &feedback)
Update the internal state maintained by the handler using information from the received feedback mess...
void clearMenuHandler()
Remove the menu handler for this interaction handler.
bool getPoseOffset(const EndEffectorInteraction &eef, geometry_msgs::msg::Pose &m)
Get the offset from EEF to its marker.
void clearError()
Clear any error settings. This makes the markers appear as if the state is no longer invalid.
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
void clearLastJointMarkerPose(const JointInteraction &vj)
Clear the last interactive_marker command pose for the given joint.
const InteractionHandlerCallbackFn & getUpdateCallback() const
virtual bool inError(const EndEffectorInteraction &eef) const
Check if the marker corresponding to this end-effector leads to an invalid state.
InteractionHandler(const std::string &name, const moveit::core::RobotModelConstPtr &model, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer=std::shared_ptr< tf2_ros::Buffer >())
void clearLastMarkerPoses()
Clear the last interactive_marker command poses for all end-effectors and joints.
virtual void handleEndEffector(const EndEffectorInteraction &eef, const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr &feedback)
Update the internal state maintained by the handler using information from the received feedback mess...
void clearLastEndEffectorMarkerPose(const EndEffectorInteraction &eef)
Clear the last interactive_marker command pose for the given end-effector.
bool transformFeedbackPose(const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr &feedback, const geometry_msgs::msg::Pose &offset, geometry_msgs::msg::PoseStamped &tpose)
void setPoseOffset(const EndEffectorInteraction &eef, const geometry_msgs::msg::Pose &m)
Set the offset from EEF to its marker.
void setMenuHandler(const std::shared_ptr< interactive_markers::MenuHandler > &mh)
Set the menu handler that defines menus and callbacks for all interactive markers drawn by this inter...
Maintain a RobotState in a multithreaded environment.
moveit::core::RobotStateConstPtr getState() const
get read-only access to the state.
void setState(const moveit::core::RobotState &state)
Set the state to the new value.
std::function< void(InteractionHandler *, bool)> InteractionHandlerCallbackFn