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>
53 #include <Eigen/Geometry>
57 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros_robot_interaction.interaction_handler");
61 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
63 , name_(fixName(
name))
65 , tf_buffer_(tf_buffer)
67 , display_meshes_(true)
68 , display_controls_(true)
73 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
75 , name_(fixName(
name))
77 , tf_buffer_(tf_buffer)
79 , display_meshes_(true)
80 , display_controls_(true)
84 std::string InteractionHandler::fixName(std::string
name)
86 std::replace(
name.begin(),
name.end(),
'_',
'-');
92 std::scoped_lock slock(offset_map_lock_);
98 std::scoped_lock slock(offset_map_lock_);
104 std::scoped_lock slock(offset_map_lock_);
110 std::scoped_lock slock(offset_map_lock_);
116 std::scoped_lock slock(offset_map_lock_);
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())
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())
145 geometry_msgs::msg::PoseStamped& ps)
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())
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())
171 std::scoped_lock slock(pose_map_lock_);
177 std::scoped_lock slock(pose_map_lock_);
183 std::scoped_lock slock(pose_map_lock_);
196 return menu_handler_;
202 menu_handler_.reset();
206 const GenericInteraction& g,
const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
210 StateChangeCallbackFn callback;
213 updateStateGeneric(*state, g, feedback, callback);
224 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
226 if (feedback->event_type != visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE)
229 geometry_msgs::msg::PoseStamped tpose;
230 geometry_msgs::msg::Pose offset;
232 offset.orientation.w = 1;
235 pose_map_lock_.lock();
237 pose_map_lock_.unlock();
242 StateChangeCallbackFn callback;
247 updateStateEndEffector(*state, eef, pose, callback);
256 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
258 if (feedback->event_type != visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE)
261 geometry_msgs::msg::PoseStamped tpose;
262 geometry_msgs::msg::Pose offset;
264 offset.orientation.w = 1;
267 pose_map_lock_.lock();
269 pose_map_lock_.unlock();
274 StateChangeCallbackFn callback;
279 updateStateJoint(*state, vj, pose, callback);
288 void InteractionHandler::updateStateGeneric(
290 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback, StateChangeCallbackFn& callback)
294 if (update_callback_)
296 cb(handler, error_state_changed);
302 const geometry_msgs::msg::Pose& pose, StateChangeCallbackFn& callback)
306 KinematicOptions kinematic_options = kinematic_options_map_->getOptions(eef.parent_group);
308 bool ok = kinematic_options.setStateFromIK(state, eef.parent_group, eef.parent_link, pose);
309 bool error_state_changed = setErrorState(eef.parent_group, !ok);
310 if (update_callback_)
312 cb(handler, error_state_changed);
318 const geometry_msgs::msg::Pose& feedback_pose,
319 StateChangeCallbackFn& callback)
321 Eigen::Isometry3d pose;
322 tf2::fromMsg(feedback_pose, pose);
330 if (update_callback_)
352 error_state_.clear();
357 bool InteractionHandler::setErrorState(
const std::string&
name,
bool new_error_state)
359 bool old_error_state = error_state_.find(
name) != error_state_.end();
361 if (new_error_state == old_error_state)
365 error_state_.insert(
name);
367 error_state_.erase(
name);
372 bool InteractionHandler::getErrorState(
const std::string&
name)
const
375 return error_state_.find(
name) != error_state_.end();
379 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback,
380 const geometry_msgs::msg::Pose& offset, geometry_msgs::msg::PoseStamped& tpose)
382 tpose.header = feedback->header;
383 tpose.pose = feedback->pose;
389 geometry_msgs::msg::PoseStamped spose(tpose);
393 tf2::Transform tf_offset, tf_tpose;
394 tf2::fromMsg(offset, tf_offset);
395 tf2::fromMsg(spose.pose, tf_tpose);
396 tf2::toMsg(tf_tpose * tf_offset.inverse(), tpose.pose);
398 catch (tf2::TransformException& e)
400 RCLCPP_ERROR(LOGGER,
"Error transforming from frame '%s' to frame '%s'", tpose.header.frame_id.c_str(),
406 RCLCPP_ERROR(LOGGER,
"Cannot transform from frame '%s' to frame '%s' (no TF instance provided)",
417 update_callback_ = callback;
423 return update_callback_;
429 display_meshes_ = visible;
435 return display_meshes_;
441 display_controls_ = visible;
447 return display_controls_;
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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 update(bool force=false)
Update all transforms.
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)
std::function< void(InteractionHandler *, bool)> InteractionHandlerCallbackFn
const rclcpp::Logger LOGGER
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.