39#include <geometry_msgs/msg/pose_stamped.hpp>
43#include <visualization_msgs/msg/interactive_marker_feedback.hpp>
44#include <interactive_markers/menu_handler.hpp>
45#include <tf2_ros/buffer.h>
82 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>());
86 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>());
90 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>());
93 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>());
154 void setMenuHandler(
const std::shared_ptr<interactive_markers::MenuHandler>& mh);
159 const std::shared_ptr<interactive_markers::MenuHandler>&
getMenuHandler();
194 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback);
199 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback);
204 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback);
222 bool transformFeedbackPose(
const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback,
223 const geometry_msgs::msg::Pose& offset, geometry_msgs::msg::PoseStamped& tpose);
235 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback,
236 StateChangeCallbackFn& callback);
241 const geometry_msgs::msg::Pose& pose, StateChangeCallbackFn& callback);
246 const geometry_msgs::msg::Pose& pose, StateChangeCallbackFn& callback);
251 bool setErrorState(
const std::string& name,
bool new_error_state);
255 bool getErrorState(
const std::string& name)
const;
264 std::map<std::string, geometry_msgs::msg::Pose> offset_map_;
273 std::map<std::string, geometry_msgs::msg::PoseStamped> pose_map_;
275 std::mutex pose_map_lock_;
276 std::mutex offset_map_lock_;
281 KinematicOptionsMapPtr kinematic_options_map_;
285 std::set<std::string> error_state_;
292 std::shared_ptr<interactive_markers::MenuHandler> menu_handler_;
302 std::function<void(
InteractionHandler* handler,
bool error_state_changed)> update_callback_;
305 bool display_meshes_;
308 bool display_controls_;
311 static std::string fixName(std::string name);
#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 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_
~InteractionHandler() override
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 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.
bool getMeshesVisible() const
bool getControlsVisible() const
const std::string & getName() 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.
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