moveit2
The MoveIt Motion Planning Framework for ROS 2.
interaction_handler.cpp
Go to the documentation of this file.
1 
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2012-2013, Willow Garage, Inc.
6  * Copyright (c) 2013, Ioan A. Sucan
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Willow Garage nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *********************************************************************/
36 
37 /* Author: Ioan Sucan, Adam Leeper */
38 
44 #include <interactive_markers/interactive_marker_server.hpp>
45 #include <interactive_markers/menu_handler.hpp>
46 // TODO: Remove conditional include when released to all active distros.
47 #if __has_include(<tf2/LinearMath/Transform.hpp>)
48 #include <tf2/LinearMath/Transform.hpp>
49 #else
50 #include <tf2/LinearMath/Transform.h>
51 #endif
52 #include <tf2_eigen/tf2_eigen.hpp>
53 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
54 #include <algorithm>
55 #include <string>
56 
57 #include <Eigen/Core>
58 #include <Eigen/Geometry>
59 
60 namespace robot_interaction
61 {
62 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros_robot_interaction.interaction_handler");
63 
64 InteractionHandler::InteractionHandler(const RobotInteractionPtr& robot_interaction, const std::string& name,
65  const moveit::core::RobotState& initial_robot_state,
66  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
67  : LockedRobotState(initial_robot_state)
68  , name_(fixName(name))
69  , planning_frame_(robot_interaction->getRobotModel()->getModelFrame())
70  , tf_buffer_(tf_buffer)
71  , kinematic_options_map_(robot_interaction->getKinematicOptionsMap())
72  , display_meshes_(true)
73  , display_controls_(true)
74 {
75 }
76 
77 InteractionHandler::InteractionHandler(const RobotInteractionPtr& robot_interaction, const std::string& name,
78  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
79  : LockedRobotState(robot_interaction->getRobotModel())
80  , name_(fixName(name))
81  , planning_frame_(robot_interaction->getRobotModel()->getModelFrame())
82  , tf_buffer_(tf_buffer)
83  , kinematic_options_map_(robot_interaction->getKinematicOptionsMap())
84  , display_meshes_(true)
85  , display_controls_(true)
86 {
87 }
88 
89 std::string InteractionHandler::fixName(std::string name)
90 {
91  std::replace(name.begin(), name.end(), '_', '-'); // we use _ as a special char in marker name
92  return name;
93 }
94 
95 void InteractionHandler::setPoseOffset(const EndEffectorInteraction& eef, const geometry_msgs::msg::Pose& m)
96 {
97  std::scoped_lock slock(offset_map_lock_);
98  offset_map_[eef.eef_group] = m;
99 }
100 
101 void InteractionHandler::setPoseOffset(const JointInteraction& vj, const geometry_msgs::msg::Pose& m)
102 {
103  std::scoped_lock slock(offset_map_lock_);
104  offset_map_[vj.joint_name] = m;
105 }
106 
108 {
109  std::scoped_lock slock(offset_map_lock_);
110  offset_map_.erase(eef.eef_group);
111 }
112 
114 {
115  std::scoped_lock slock(offset_map_lock_);
116  offset_map_.erase(vj.joint_name);
117 }
118 
120 {
121  std::scoped_lock slock(offset_map_lock_);
122  offset_map_.clear();
123 }
124 
125 bool InteractionHandler::getPoseOffset(const EndEffectorInteraction& eef, geometry_msgs::msg::Pose& m)
126 {
127  std::scoped_lock slock(offset_map_lock_);
128  std::map<std::string, geometry_msgs::msg::Pose>::iterator it = offset_map_.find(eef.eef_group);
129  if (it != offset_map_.end())
130  {
131  m = it->second;
132  return true;
133  }
134  return false;
135 }
136 
137 bool InteractionHandler::getPoseOffset(const JointInteraction& vj, geometry_msgs::msg::Pose& m)
138 {
139  std::scoped_lock slock(offset_map_lock_);
140  std::map<std::string, geometry_msgs::msg::Pose>::iterator it = offset_map_.find(vj.joint_name);
141  if (it != offset_map_.end())
142  {
143  m = it->second;
144  return true;
145  }
146  return false;
147 }
148 
150  geometry_msgs::msg::PoseStamped& ps)
151 {
152  std::scoped_lock slock(pose_map_lock_);
153  std::map<std::string, geometry_msgs::msg::PoseStamped>::iterator it = pose_map_.find(eef.eef_group);
154  if (it != pose_map_.end())
155  {
156  ps = it->second;
157  return true;
158  }
159  return false;
160 }
161 
162 bool InteractionHandler::getLastJointMarkerPose(const JointInteraction& vj, geometry_msgs::msg::PoseStamped& ps)
163 {
164  std::scoped_lock slock(pose_map_lock_);
165  std::map<std::string, geometry_msgs::msg::PoseStamped>::iterator it = pose_map_.find(vj.joint_name);
166  if (it != pose_map_.end())
167  {
168  ps = it->second;
169  return true;
170  }
171  return false;
172 }
173 
175 {
176  std::scoped_lock slock(pose_map_lock_);
177  pose_map_.erase(eef.eef_group);
178 }
179 
181 {
182  std::scoped_lock slock(pose_map_lock_);
183  pose_map_.erase(vj.joint_name);
184 }
185 
187 {
188  std::scoped_lock slock(pose_map_lock_);
189  pose_map_.clear();
190 }
191 
192 void InteractionHandler::setMenuHandler(const std::shared_ptr<interactive_markers::MenuHandler>& mh)
193 {
194  std::scoped_lock lock(state_lock_);
195  menu_handler_ = mh;
196 }
197 
198 const std::shared_ptr<interactive_markers::MenuHandler>& InteractionHandler::getMenuHandler()
199 {
200  std::scoped_lock lock(state_lock_);
201  return menu_handler_;
202 }
203 
205 {
206  std::scoped_lock lock(state_lock_);
207  menu_handler_.reset();
208 }
209 
211  const GenericInteraction& g, const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
212 {
213  if (g.process_feedback)
214  {
215  StateChangeCallbackFn callback;
216  // modify the RobotState in-place with the state_lock_ held.
217  LockedRobotState::modifyState([this, &g, &feedback, &callback](moveit::core::RobotState* state) {
218  updateStateGeneric(*state, g, feedback, callback);
219  });
220 
221  // This calls update_callback_ to notify client that state changed.
222  if (callback)
223  callback(this);
224  }
225 }
226 
228  const EndEffectorInteraction& eef,
229  const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
230 {
231  if (feedback->event_type != visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE)
232  return;
233 
234  geometry_msgs::msg::PoseStamped tpose;
235  geometry_msgs::msg::Pose offset;
236  if (!getPoseOffset(eef, offset))
237  offset.orientation.w = 1;
238  if (transformFeedbackPose(feedback, offset, tpose))
239  {
240  pose_map_lock_.lock();
241  pose_map_[eef.eef_group] = tpose;
242  pose_map_lock_.unlock();
243  }
244  else
245  return;
246 
247  StateChangeCallbackFn callback;
248 
249  // modify the RobotState in-place with state_lock_ held.
250  // This locks state_lock_ before calling updateState()
251  LockedRobotState::modifyState([this, &eef, &pose = tpose.pose, &callback](moveit::core::RobotState* state) {
252  updateStateEndEffector(*state, eef, pose, callback);
253  });
254 
255  // This calls update_callback_ to notify client that state changed.
256  if (callback)
257  callback(this);
258 }
259 
261  const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
262 {
263  if (feedback->event_type != visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE)
264  return;
265 
266  geometry_msgs::msg::PoseStamped tpose;
267  geometry_msgs::msg::Pose offset;
268  if (!getPoseOffset(vj, offset))
269  offset.orientation.w = 1;
270  if (transformFeedbackPose(feedback, offset, tpose))
271  {
272  pose_map_lock_.lock();
273  pose_map_[vj.joint_name] = tpose;
274  pose_map_lock_.unlock();
275  }
276  else
277  return;
278 
279  StateChangeCallbackFn callback;
280 
281  // modify the RobotState in-place with state_lock_ held.
282  // This locks state_lock_ before calling updateState()
283  LockedRobotState::modifyState([this, &vj, &pose = tpose.pose, &callback](moveit::core::RobotState* state) {
284  updateStateJoint(*state, vj, pose, callback);
285  });
286 
287  // This calls update_callback_ to notify client that state changed.
288  if (callback)
289  callback(this);
290 }
291 
292 // MUST hold state_lock_ when calling this!
293 void InteractionHandler::updateStateGeneric(
295  const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback, StateChangeCallbackFn& callback)
296 {
297  bool ok = g.process_feedback(state, feedback);
298  bool error_state_changed = setErrorState(g.marker_name_suffix, !ok);
299  if (update_callback_)
300  callback = [cb = this->update_callback_, error_state_changed](robot_interaction::InteractionHandler* handler) {
301  cb(handler, error_state_changed);
302  };
303 }
304 
305 // MUST hold state_lock_ when calling this!
306 void InteractionHandler::updateStateEndEffector(moveit::core::RobotState& state, const EndEffectorInteraction& eef,
307  const geometry_msgs::msg::Pose& pose, StateChangeCallbackFn& callback)
308 {
309  // This is called with state_lock_ held, so no additional locking needed to
310  // access kinematic_options_map_.
311  KinematicOptions kinematic_options = kinematic_options_map_->getOptions(eef.parent_group);
312 
313  bool ok = kinematic_options.setStateFromIK(state, eef.parent_group, eef.parent_link, pose);
314  bool error_state_changed = setErrorState(eef.parent_group, !ok);
315  if (update_callback_)
316  callback = [cb = this->update_callback_, error_state_changed](robot_interaction::InteractionHandler* handler) {
317  cb(handler, error_state_changed);
318  };
319 }
320 
321 // MUST hold state_lock_ when calling this!
322 void InteractionHandler::updateStateJoint(moveit::core::RobotState& state, const JointInteraction& vj,
323  const geometry_msgs::msg::Pose& feedback_pose,
324  StateChangeCallbackFn& callback)
325 {
326  Eigen::Isometry3d pose;
327  tf2::fromMsg(feedback_pose, pose);
328 
329  if (!vj.parent_frame.empty() && !moveit::core::Transforms::sameFrame(vj.parent_frame, planning_frame_))
330  pose = state.getGlobalLinkTransform(vj.parent_frame).inverse() * pose;
331 
332  state.setJointPositions(vj.joint_name, pose);
333  state.update();
334 
335  if (update_callback_)
336  callback = [cb = this->update_callback_](robot_interaction::InteractionHandler* handler) { cb(handler, false); };
337 }
338 
340 {
341  return getErrorState(eef.parent_group);
342 }
343 
345 {
346  return getErrorState(g.marker_name_suffix);
347 }
348 
349 bool InteractionHandler::inError(const JointInteraction& /*unused*/) const
350 {
351  return false;
352 }
353 
355 {
356  std::scoped_lock lock(state_lock_);
357  error_state_.clear();
358 }
359 
360 // return true if the state changed.
361 // MUST hold state_lock_ when calling this!
362 bool InteractionHandler::setErrorState(const std::string& name, bool new_error_state)
363 {
364  bool old_error_state = error_state_.find(name) != error_state_.end();
365 
366  if (new_error_state == old_error_state)
367  return false;
368 
369  if (new_error_state)
370  error_state_.insert(name);
371  else
372  error_state_.erase(name);
373 
374  return true;
375 }
376 
377 bool InteractionHandler::getErrorState(const std::string& name) const
378 {
379  std::scoped_lock lock(state_lock_);
380  return error_state_.find(name) != error_state_.end();
381 }
382 
384  const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback,
385  const geometry_msgs::msg::Pose& offset, geometry_msgs::msg::PoseStamped& tpose)
386 {
387  tpose.header = feedback->header;
388  tpose.pose = feedback->pose;
389  if (feedback->header.frame_id != planning_frame_)
390  {
391  if (tf_buffer_)
392  try
393  {
394  geometry_msgs::msg::PoseStamped spose(tpose);
395  // Express feedback (marker) pose in planning frame
396  tf_buffer_->transform(tpose, spose, planning_frame_);
397  // Apply inverse of offset to bring feedback pose back into the end-effector support link frame
398  tf2::Transform tf_offset, tf_tpose;
399  tf2::fromMsg(offset, tf_offset);
400  tf2::fromMsg(spose.pose, tf_tpose);
401  tf2::toMsg(tf_tpose * tf_offset.inverse(), tpose.pose);
402  }
403  catch (tf2::TransformException& e)
404  {
405  RCLCPP_ERROR(LOGGER, "Error transforming from frame '%s' to frame '%s'", tpose.header.frame_id.c_str(),
406  planning_frame_.c_str());
407  return false;
408  }
409  else
410  {
411  RCLCPP_ERROR(LOGGER, "Cannot transform from frame '%s' to frame '%s' (no TF instance provided)",
412  tpose.header.frame_id.c_str(), planning_frame_.c_str());
413  return false;
414  }
415  }
416  return true;
417 }
418 
420 {
421  std::scoped_lock lock(state_lock_);
422  update_callback_ = callback;
423 }
424 
426 {
427  std::scoped_lock lock(state_lock_);
428  return update_callback_;
429 }
430 
432 {
433  std::scoped_lock lock(state_lock_);
434  display_meshes_ = visible;
435 }
436 
438 {
439  std::scoped_lock lock(state_lock_);
440  return display_meshes_;
441 }
442 
444 {
445  std::scoped_lock lock(state_lock_);
446  display_controls_ = visible;
447 }
448 
450 {
451  std::scoped_lock lock(state_lock_);
452  return display_controls_;
453 }
454 } // namespace robot_interaction
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
Definition: robot_state.h:1340
void update(bool force=false)
Update all transforms.
void setJointPositions(const std::string &joint_name, const double *position)
Definition: robot_state.h:515
static bool sameFrame(const std::string &frame1, const std::string &frame2)
Check if two frames end up being the same once the missing / are added as prefix (if they are missing...
Definition: transforms.cpp:64
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.
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 RobotInteractionPtr &robot_interaction, 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 >())
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.
void modifyState(const ModifyStateFunction &modify)
std::function< void(InteractionHandler *, bool)> InteractionHandlerCallbackFn
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31
std::string parent_group
The name of the group that sustains the end-effector (usually an arm)
Definition: interaction.h:142
std::string eef_group
The name of the group that defines the group joints.
Definition: interaction.h:148
std::string joint_name
The name of the joint.
Definition: interaction.h:168