moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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#include <tf2/LinearMath/Transform.h>
47#include <tf2_eigen/tf2_eigen.hpp>
48#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
50#include <algorithm>
51#include <string>
52
53#include <Eigen/Core>
54#include <Eigen/Geometry>
55
56namespace robot_interaction
57{
58
59InteractionHandler::InteractionHandler(const RobotInteractionPtr& robot_interaction, const std::string& name,
60 const moveit::core::RobotState& initial_robot_state,
61 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
62 : LockedRobotState(initial_robot_state)
63 , name_(fixName(name))
64 , planning_frame_(robot_interaction->getRobotModel()->getModelFrame())
65 , tf_buffer_(tf_buffer)
66 , kinematic_options_map_(robot_interaction->getKinematicOptionsMap())
67 , display_meshes_(true)
68 , display_controls_(true)
69{
70}
71
72InteractionHandler::InteractionHandler(const RobotInteractionPtr& robot_interaction, const std::string& name,
73 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
74 : LockedRobotState(robot_interaction->getRobotModel())
75 , name_(fixName(name))
76 , planning_frame_(robot_interaction->getRobotModel()->getModelFrame())
77 , tf_buffer_(tf_buffer)
78 , kinematic_options_map_(robot_interaction->getKinematicOptionsMap())
79 , display_meshes_(true)
80 , display_controls_(true)
81{
82}
83
84std::string InteractionHandler::fixName(std::string name)
85{
86 std::replace(name.begin(), name.end(), '_', '-'); // we use _ as a special char in marker name
87 return name;
88}
89
90void InteractionHandler::setPoseOffset(const EndEffectorInteraction& eef, const geometry_msgs::msg::Pose& m)
91{
92 std::scoped_lock slock(offset_map_lock_);
93 offset_map_[eef.eef_group] = m;
94}
95
96void InteractionHandler::setPoseOffset(const JointInteraction& vj, const geometry_msgs::msg::Pose& m)
97{
98 std::scoped_lock slock(offset_map_lock_);
99 offset_map_[vj.joint_name] = m;
100}
101
103{
104 std::scoped_lock slock(offset_map_lock_);
105 offset_map_.erase(eef.eef_group);
106}
107
109{
110 std::scoped_lock slock(offset_map_lock_);
111 offset_map_.erase(vj.joint_name);
112}
113
115{
116 std::scoped_lock slock(offset_map_lock_);
117 offset_map_.clear();
118}
119
120bool InteractionHandler::getPoseOffset(const EndEffectorInteraction& eef, geometry_msgs::msg::Pose& m)
121{
122 std::scoped_lock slock(offset_map_lock_);
123 std::map<std::string, geometry_msgs::msg::Pose>::iterator it = offset_map_.find(eef.eef_group);
124 if (it != offset_map_.end())
125 {
126 m = it->second;
127 return true;
128 }
129 return false;
130}
131
132bool InteractionHandler::getPoseOffset(const JointInteraction& vj, geometry_msgs::msg::Pose& m)
133{
134 std::scoped_lock slock(offset_map_lock_);
135 std::map<std::string, geometry_msgs::msg::Pose>::iterator it = offset_map_.find(vj.joint_name);
136 if (it != offset_map_.end())
137 {
138 m = it->second;
139 return true;
140 }
141 return false;
142}
143
145 geometry_msgs::msg::PoseStamped& ps)
146{
147 std::scoped_lock slock(pose_map_lock_);
148 std::map<std::string, geometry_msgs::msg::PoseStamped>::iterator it = pose_map_.find(eef.eef_group);
149 if (it != pose_map_.end())
150 {
151 ps = it->second;
152 return true;
153 }
154 return false;
155}
156
157bool InteractionHandler::getLastJointMarkerPose(const JointInteraction& vj, geometry_msgs::msg::PoseStamped& ps)
158{
159 std::scoped_lock slock(pose_map_lock_);
160 std::map<std::string, geometry_msgs::msg::PoseStamped>::iterator it = pose_map_.find(vj.joint_name);
161 if (it != pose_map_.end())
162 {
163 ps = it->second;
164 return true;
165 }
166 return false;
167}
168
170{
171 std::scoped_lock slock(pose_map_lock_);
172 pose_map_.erase(eef.eef_group);
173}
174
176{
177 std::scoped_lock slock(pose_map_lock_);
178 pose_map_.erase(vj.joint_name);
179}
180
182{
183 std::scoped_lock slock(pose_map_lock_);
184 pose_map_.clear();
185}
186
187void InteractionHandler::setMenuHandler(const std::shared_ptr<interactive_markers::MenuHandler>& mh)
188{
189 std::scoped_lock lock(state_lock_);
190 menu_handler_ = mh;
191}
192
193const std::shared_ptr<interactive_markers::MenuHandler>& InteractionHandler::getMenuHandler()
194{
195 std::scoped_lock lock(state_lock_);
196 return menu_handler_;
197}
198
200{
201 std::scoped_lock lock(state_lock_);
202 menu_handler_.reset();
203}
204
206 const GenericInteraction& g, const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
207{
208 if (g.process_feedback)
209 {
210 StateChangeCallbackFn callback;
211 // modify the RobotState in-place with the state_lock_ held.
212 LockedRobotState::modifyState([this, &g, &feedback, &callback](moveit::core::RobotState* state) {
213 updateStateGeneric(*state, g, feedback, callback);
214 });
215
216 // This calls update_callback_ to notify client that state changed.
217 if (callback)
218 callback(this);
219 }
220}
221
223 const EndEffectorInteraction& eef,
224 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
225{
226 if (feedback->event_type != visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE)
227 return;
228
229 geometry_msgs::msg::PoseStamped tpose;
230 geometry_msgs::msg::Pose offset;
231 if (!getPoseOffset(eef, offset))
232 offset.orientation.w = 1;
233 if (transformFeedbackPose(feedback, offset, tpose))
234 {
235 pose_map_lock_.lock();
236 pose_map_[eef.eef_group] = tpose;
237 pose_map_lock_.unlock();
238 }
239 else
240 return;
241
242 StateChangeCallbackFn callback;
243
244 // modify the RobotState in-place with state_lock_ held.
245 // This locks state_lock_ before calling updateState()
246 LockedRobotState::modifyState([this, &eef, &pose = tpose.pose, &callback](moveit::core::RobotState* state) {
247 updateStateEndEffector(*state, eef, pose, callback);
248 });
249
250 // This calls update_callback_ to notify client that state changed.
251 if (callback)
252 callback(this);
253}
254
256 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
257{
258 if (feedback->event_type != visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE)
259 return;
260
261 geometry_msgs::msg::PoseStamped tpose;
262 geometry_msgs::msg::Pose offset;
263 if (!getPoseOffset(vj, offset))
264 offset.orientation.w = 1;
265 if (transformFeedbackPose(feedback, offset, tpose))
266 {
267 pose_map_lock_.lock();
268 pose_map_[vj.joint_name] = tpose;
269 pose_map_lock_.unlock();
270 }
271 else
272 return;
273
274 StateChangeCallbackFn callback;
275
276 // modify the RobotState in-place with state_lock_ held.
277 // This locks state_lock_ before calling updateState()
278 LockedRobotState::modifyState([this, &vj, &pose = tpose.pose, &callback](moveit::core::RobotState* state) {
279 updateStateJoint(*state, vj, pose, callback);
280 });
281
282 // This calls update_callback_ to notify client that state changed.
283 if (callback)
284 callback(this);
285}
286
287// MUST hold state_lock_ when calling this!
288void InteractionHandler::updateStateGeneric(
290 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback, StateChangeCallbackFn& callback)
291{
292 bool ok = g.process_feedback(state, feedback);
293 bool error_state_changed = setErrorState(g.marker_name_suffix, !ok);
294 if (update_callback_)
295 {
296 callback = [cb = update_callback_, error_state_changed](robot_interaction::InteractionHandler* handler) {
297 cb(handler, error_state_changed);
298 };
299 }
300}
301
302// MUST hold state_lock_ when calling this!
303void InteractionHandler::updateStateEndEffector(moveit::core::RobotState& state, const EndEffectorInteraction& eef,
304 const geometry_msgs::msg::Pose& pose, StateChangeCallbackFn& callback)
305{
306 // This is called with state_lock_ held, so no additional locking needed to
307 // access kinematic_options_map_.
308 KinematicOptions kinematic_options = kinematic_options_map_->getOptions(eef.parent_group);
309
310 bool ok = kinematic_options.setStateFromIK(state, eef.parent_group, eef.parent_link, pose);
311 bool error_state_changed = setErrorState(eef.parent_group, !ok);
312 if (update_callback_)
313 {
314 callback = [cb = update_callback_, error_state_changed](robot_interaction::InteractionHandler* handler) {
315 cb(handler, error_state_changed);
316 };
317 }
318}
319
320// MUST hold state_lock_ when calling this!
321void InteractionHandler::updateStateJoint(moveit::core::RobotState& state, const JointInteraction& vj,
322 const geometry_msgs::msg::Pose& feedback_pose,
323 StateChangeCallbackFn& callback)
324{
325 Eigen::Isometry3d pose;
326 tf2::fromMsg(feedback_pose, pose);
327
328 if (!vj.parent_frame.empty() && !moveit::core::Transforms::sameFrame(vj.parent_frame, planning_frame_))
329 pose = state.getGlobalLinkTransform(vj.parent_frame).inverse() * pose;
330
331 state.setJointPositions(vj.joint_name, pose);
332 state.update();
333
334 if (update_callback_)
335 callback = [cb = update_callback_](robot_interaction::InteractionHandler* handler) { cb(handler, false); };
336}
337
339{
340 return getErrorState(eef.parent_group);
341}
342
344{
345 return getErrorState(g.marker_name_suffix);
346}
347
349{
350 return false;
351}
352
354{
355 std::scoped_lock lock(state_lock_);
356 error_state_.clear();
357}
358
359// return true if the state changed.
360// MUST hold state_lock_ when calling this!
361bool InteractionHandler::setErrorState(const std::string& name, bool new_error_state)
362{
363 bool old_error_state = error_state_.find(name) != error_state_.end();
364
365 if (new_error_state == old_error_state)
366 return false;
367
368 if (new_error_state)
369 {
370 error_state_.insert(name);
371 }
372 else
373 {
374 error_state_.erase(name);
375 }
376
377 return true;
378}
379
380bool InteractionHandler::getErrorState(const std::string& name) const
381{
382 std::scoped_lock lock(state_lock_);
383 return error_state_.find(name) != error_state_.end();
384}
385
387 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback,
388 const geometry_msgs::msg::Pose& offset, geometry_msgs::msg::PoseStamped& tpose)
389{
390 tpose.header = feedback->header;
391 tpose.pose = feedback->pose;
392 if (feedback->header.frame_id != planning_frame_)
393 {
394 if (tf_buffer_)
395 {
396 try
397 {
398 geometry_msgs::msg::PoseStamped spose(tpose);
399 // Express feedback (marker) pose in planning frame
400 tf_buffer_->transform(tpose, spose, planning_frame_);
401 // Apply inverse of offset to bring feedback pose back into the end-effector support link frame
402 tf2::Transform tf_offset, tf_tpose;
403 tf2::fromMsg(offset, tf_offset);
404 tf2::fromMsg(spose.pose, tf_tpose);
405 tf2::toMsg(tf_tpose * tf_offset.inverse(), tpose.pose);
406 }
407 catch (tf2::TransformException& e)
408 {
409 RCLCPP_ERROR(moveit::getLogger("moveit.ros.interaction_handler"),
410 "Error transforming from frame '%s' to frame '%s'", tpose.header.frame_id.c_str(),
411 planning_frame_.c_str());
412 return false;
413 }
414 }
415 else
416 {
417 RCLCPP_ERROR(moveit::getLogger("moveit.ros.interaction_handler"),
418 "Cannot transform from frame '%s' to frame '%s' (no TF instance provided)",
419 tpose.header.frame_id.c_str(), planning_frame_.c_str());
420 return false;
421 }
422 }
423 return true;
424}
425
427{
428 std::scoped_lock lock(state_lock_);
429 update_callback_ = callback;
430}
431
433{
434 std::scoped_lock lock(state_lock_);
435 return update_callback_;
436}
437
439{
440 std::scoped_lock lock(state_lock_);
441 display_meshes_ = visible;
442}
443
445{
446 std::scoped_lock lock(state_lock_);
447 return display_meshes_;
448}
449
451{
452 std::scoped_lock lock(state_lock_);
453 display_controls_ = visible;
454}
455
457{
458 std::scoped_lock lock(state_lock_);
459 return display_controls_;
460}
461} // namespace robot_interaction
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void update(bool force=false)
Update all transforms.
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...
void setJointPositions(const std::string &joint_name, const double *position)
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...
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)
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
std::function< void(InteractionHandler *, bool)> InteractionHandlerCallbackFn
std::string parent_group
The name of the group that sustains the end-effector (usually an arm)
std::string eef_group
The name of the group that defines the group joints.
std::string joint_name
The name of the joint.