Class InteractionHandler
Defined in File interaction_handler.h
Inheritance Relationships
Base Type
public robot_interaction::LockedRobotState
(Class LockedRobotState)
Class Documentation
-
class InteractionHandler : public robot_interaction::LockedRobotState
Manage interactive markers to control a RobotState.
Each instance maintains one or more interactive markers to control various joints in one group of one RobotState. The group being controlled is maintained by the RobotInteraction object that contains this InteractionHandler object. All InteractionHandler objects in the same RobotInteraction are controlling the same group.
Public Functions
-
inline ~InteractionHandler() override
-
inline const std::string &getName() const
-
void setUpdateCallback(const InteractionHandlerCallbackFn &callback)
-
const InteractionHandlerCallbackFn &getUpdateCallback() const
-
void setMeshesVisible(bool visible)
-
bool getMeshesVisible() const
-
void setControlsVisible(bool visible)
-
bool getControlsVisible() const
-
void setPoseOffset(const EndEffectorInteraction &eef, const geometry_msgs::msg::Pose &m)
Set the offset from EEF to its marker.
- Parameters:
eef – The target end-effector.
m – The pose of the marker in the frame of the end-effector parent.
-
void setPoseOffset(const JointInteraction &j, const geometry_msgs::msg::Pose &m)
Set the offset from a joint to its marker.
- Parameters:
j – The target joint.
m – The pose of the marker in the frame of the joint parent.
-
bool getPoseOffset(const EndEffectorInteraction &eef, geometry_msgs::msg::Pose &m)
Get the offset from EEF to its marker.
- Parameters:
The – target end-effector.
The – pose offset (only valid if return value is true).
- Returns:
True if an offset was found for the given end-effector.
-
bool getPoseOffset(const JointInteraction &vj, geometry_msgs::msg::Pose &m)
Get the offset from a joint to its marker.
- Parameters:
vj – The joint.
m – The pose offset (only valid if return value is true).
- Returns:
True if an offset was found for the given joint.
-
void clearPoseOffset(const EndEffectorInteraction &eef)
Clear the interactive marker pose offset for the given end-effector.
- Parameters:
The – target end-effector.
-
void clearPoseOffset(const JointInteraction &vj)
Clear the interactive marker pose offset for the given joint.
- Parameters:
The – target joint.
-
void clearPoseOffsets()
Clear the pose offset for all end-effectors and virtual joints.
Set the menu handler that defines menus and callbacks for all interactive markers drawn by this interaction handler.
- Parameters:
A – menu handler.
-
const std::shared_ptr<interactive_markers::MenuHandler> &getMenuHandler()
Get the menu handler that defines menus and callbacks for all interactive markers drawn by this interaction handler.
- Returns:
The menu handler.
-
void clearMenuHandler()
Remove the menu handler for this interaction handler.
-
bool getLastEndEffectorMarkerPose(const EndEffectorInteraction &eef, geometry_msgs::msg::PoseStamped &pose)
Get the last interactive_marker command pose for an end-effector.
- Parameters:
The – end-effector in question.
A – PoseStamped message containing the last (offset-removed) pose commanded for the end-effector.
- Returns:
True if a pose for that end-effector was found, false otherwise.
-
bool getLastJointMarkerPose(const JointInteraction &vj, geometry_msgs::msg::PoseStamped &pose)
Get the last interactive_marker command pose for a joint.
- Parameters:
The – joint in question.
A – PoseStamped message containing the last (offset-removed) pose commanded for the joint.
- Returns:
True if a pose for that joint was found, false otherwise.
-
void clearLastEndEffectorMarkerPose(const EndEffectorInteraction &eef)
Clear the last interactive_marker command pose for the given end-effector.
- Parameters:
The – target end-effector.
-
void clearLastJointMarkerPose(const JointInteraction &vj)
Clear the last interactive_marker command pose for the given joint.
- Parameters:
The – target joint.
-
void clearLastMarkerPoses()
Clear the last interactive_marker command poses for all end-effectors and joints.
Update the internal state maintained by the handler using information from the received feedback message.
Update the internal state maintained by the handler using information from the received feedback message.
Update the internal state maintained by the handler using information from the received feedback message.
-
virtual bool inError(const EndEffectorInteraction &eef) const
Check if the marker corresponding to this end-effector leads to an invalid state.
-
virtual bool inError(const JointInteraction &vj) const
Check if the marker corresponding to this joint leads to an invalid state.
-
virtual bool inError(const GenericInteraction &g) const
Check if the generic marker to an invalid state.
-
void clearError()
Clear any error settings. This makes the markers appear as if the state is no longer invalid.
-
moveit::core::RobotStateConstPtr getState() const
Get a copy of the RobotState maintained by this InteractionHandler.
-
void setState(const moveit::core::RobotState &state)
Set a new RobotState for this InteractionHandler.
Protected Functions
-
inline ~InteractionHandler() override