44#include <interactive_markers/interactive_marker_server.hpp>
45#include <interactive_markers/menu_handler.hpp>
47#if __has_include(<tf2/LinearMath/Transform.hpp>)
48#include <tf2/LinearMath/Transform.hpp>
50#include <tf2/LinearMath/Transform.h>
52#include <tf2_eigen/tf2_eigen.hpp>
53#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
59#include <Eigen/Geometry>
66 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
68 , name_(fixName(name))
70 , tf_buffer_(tf_buffer)
72 , display_meshes_(true)
73 , display_controls_(true)
78 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
80 , name_(fixName(name))
82 , tf_buffer_(tf_buffer)
84 , display_meshes_(true)
85 , display_controls_(true)
89std::string InteractionHandler::fixName(std::string name)
91 std::replace(name.begin(), name.end(),
'_',
'-');
97 std::scoped_lock slock(offset_map_lock_);
103 std::scoped_lock slock(offset_map_lock_);
109 std::scoped_lock slock(offset_map_lock_);
115 std::scoped_lock slock(offset_map_lock_);
121 std::scoped_lock slock(offset_map_lock_);
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())
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())
150 geometry_msgs::msg::PoseStamped& ps)
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())
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())
176 std::scoped_lock slock(pose_map_lock_);
182 std::scoped_lock slock(pose_map_lock_);
188 std::scoped_lock slock(pose_map_lock_);
201 return menu_handler_;
207 menu_handler_.reset();
211 const GenericInteraction& g,
const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
215 StateChangeCallbackFn callback;
218 updateStateGeneric(*state, g, feedback, callback);
229 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
231 if (feedback->event_type != visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE)
234 geometry_msgs::msg::PoseStamped tpose;
235 geometry_msgs::msg::Pose offset;
237 offset.orientation.w = 1;
240 pose_map_lock_.lock();
242 pose_map_lock_.unlock();
247 StateChangeCallbackFn callback;
252 updateStateEndEffector(*state, eef, pose, callback);
261 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
263 if (feedback->event_type != visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE)
266 geometry_msgs::msg::PoseStamped tpose;
267 geometry_msgs::msg::Pose offset;
269 offset.orientation.w = 1;
272 pose_map_lock_.lock();
274 pose_map_lock_.unlock();
279 StateChangeCallbackFn callback;
284 updateStateJoint(*state, vj, pose, callback);
293void InteractionHandler::updateStateGeneric(
295 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback, StateChangeCallbackFn& callback)
299 if (update_callback_)
302 cb(handler, error_state_changed);
309 const geometry_msgs::msg::Pose& pose, StateChangeCallbackFn& callback)
313 KinematicOptions kinematic_options = kinematic_options_map_->getOptions(eef.parent_group);
315 bool ok = kinematic_options.setStateFromIK(state, eef.parent_group, eef.parent_link, pose);
316 bool error_state_changed = setErrorState(eef.parent_group, !ok);
317 if (update_callback_)
320 cb(handler, error_state_changed);
327 const geometry_msgs::msg::Pose& feedback_pose,
328 StateChangeCallbackFn& callback)
330 Eigen::Isometry3d pose;
331 tf2::fromMsg(feedback_pose, pose);
339 if (update_callback_)
361 error_state_.clear();
366bool InteractionHandler::setErrorState(
const std::string& name,
bool new_error_state)
368 bool old_error_state = error_state_.find(name) != error_state_.end();
370 if (new_error_state == old_error_state)
375 error_state_.insert(name);
379 error_state_.erase(name);
385bool InteractionHandler::getErrorState(
const std::string& name)
const
388 return error_state_.find(name) != error_state_.end();
392 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback,
393 const geometry_msgs::msg::Pose& offset, geometry_msgs::msg::PoseStamped& tpose)
395 tpose.header = feedback->header;
396 tpose.pose = feedback->pose;
403 geometry_msgs::msg::PoseStamped spose(tpose);
407 tf2::Transform tf_offset, tf_tpose;
408 tf2::fromMsg(offset, tf_offset);
409 tf2::fromMsg(spose.pose, tf_tpose);
410 tf2::toMsg(tf_tpose * tf_offset.inverse(), tpose.pose);
412 catch (tf2::TransformException& e)
415 "Error transforming from frame '%s' to frame '%s'", tpose.header.frame_id.c_str(),
423 "Cannot transform from frame '%s' to frame '%s' (no TF instance provided)",
434 update_callback_ = callback;
440 return update_callback_;
446 display_meshes_ = visible;
452 return display_meshes_;
458 display_controls_ = visible;
464 return display_controls_;
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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)
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 setControlsVisible(bool visible)
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.
void setMeshesVisible(bool visible)
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.
bool getMeshesVisible() const
bool getControlsVisible() const
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.
const std::string planning_frame_
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.
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 marker_name_suffix
ProcessFeedbackFn process_feedback
std::string joint_name
The name of the joint.