moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
robot_interaction::InteractionHandler Class Reference

#include <interaction_handler.h>

Inheritance diagram for robot_interaction::InteractionHandler:
Inheritance graph
[legend]
Collaboration diagram for robot_interaction::InteractionHandler:
Collaboration graph
[legend]

Public Member Functions

 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 >())
 
 InteractionHandler (const RobotInteractionPtr &robot_interaction, const std::string &name, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer=std::shared_ptr< tf2_ros::Buffer >())
 
 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 >())
 
 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 >())
 
 ~InteractionHandler () override
 
const std::string & getName () const
 
void setUpdateCallback (const InteractionHandlerCallbackFn &callback)
 
const InteractionHandlerCallbackFngetUpdateCallback () 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.
 
void setPoseOffset (const JointInteraction &j, const geometry_msgs::msg::Pose &m)
 Set the offset from a joint to its marker.
 
bool getPoseOffset (const EndEffectorInteraction &eef, geometry_msgs::msg::Pose &m)
 Get the offset from EEF to its marker.
 
bool getPoseOffset (const JointInteraction &vj, geometry_msgs::msg::Pose &m)
 Get the offset from a joint to its marker.
 
void clearPoseOffset (const EndEffectorInteraction &eef)
 Clear the interactive marker pose offset for the given end-effector.
 
void clearPoseOffset (const JointInteraction &vj)
 Clear the interactive marker pose offset for the given joint.
 
void clearPoseOffsets ()
 Clear the pose offset for all end-effectors and virtual joints.
 
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 interaction 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.
 
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.
 
bool getLastJointMarkerPose (const JointInteraction &vj, geometry_msgs::msg::PoseStamped &pose)
 Get the last interactive_marker command pose for a joint.
 
void clearLastEndEffectorMarkerPose (const EndEffectorInteraction &eef)
 Clear the last interactive_marker command pose for the given end-effector.
 
void clearLastJointMarkerPose (const JointInteraction &vj)
 Clear the last interactive_marker command pose for the given joint.
 
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 message.
 
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 message.
 
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 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.
 
- Public Member Functions inherited from robot_interaction::LockedRobotState
 LockedRobotState (const moveit::core::RobotState &state)
 
 LockedRobotState (const moveit::core::RobotModelPtr &model)
 
virtual ~LockedRobotState ()
 
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.
 
void modifyState (const ModifyStateFunction &modify)
 

Protected Member Functions

bool transformFeedbackPose (const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr &feedback, const geometry_msgs::msg::Pose &offset, geometry_msgs::msg::PoseStamped &tpose)
 
- Protected Member Functions inherited from robot_interaction::LockedRobotState
virtual void robotStateChanged ()
 

Protected Attributes

const std::string name_
 
const std::string planning_frame_
 
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
 
- Protected Attributes inherited from robot_interaction::LockedRobotState
std::mutex state_lock_
 

Additional Inherited Members

- Public Types inherited from robot_interaction::LockedRobotState
typedef std::function< void(moveit::core::RobotState *)> ModifyStateFunction
 

Detailed Description

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.

Definition at line 76 of file interaction_handler.h.

Constructor & Destructor Documentation

◆ InteractionHandler() [1/4]

robot_interaction::InteractionHandler::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>() 
)

Definition at line 59 of file interaction_handler.cpp.

◆ InteractionHandler() [2/4]

robot_interaction::InteractionHandler::InteractionHandler ( const RobotInteractionPtr &  robot_interaction,
const std::string &  name,
const std::shared_ptr< tf2_ros::Buffer > &  tf_buffer = std::shared_ptr<tf2_ros::Buffer>() 
)

Definition at line 72 of file interaction_handler.cpp.

◆ InteractionHandler() [3/4]

robot_interaction::InteractionHandler::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 >() 
)

◆ InteractionHandler() [4/4]

robot_interaction::InteractionHandler::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 >() 
)

◆ ~InteractionHandler()

robot_interaction::InteractionHandler::~InteractionHandler ( )
inlineoverride

Definition at line 95 of file interaction_handler.h.

Member Function Documentation

◆ clearError()

void robot_interaction::InteractionHandler::clearError ( )

Clear any error settings. This makes the markers appear as if the state is no longer invalid.

Definition at line 353 of file interaction_handler.cpp.

◆ clearLastEndEffectorMarkerPose()

void robot_interaction::InteractionHandler::clearLastEndEffectorMarkerPose ( const EndEffectorInteraction eef)

Clear the last interactive_marker command pose for the given end-effector.

Parameters
Thetarget end-effector.

Definition at line 169 of file interaction_handler.cpp.

◆ clearLastJointMarkerPose()

void robot_interaction::InteractionHandler::clearLastJointMarkerPose ( const JointInteraction vj)

Clear the last interactive_marker command pose for the given joint.

Parameters
Thetarget joint.

Definition at line 175 of file interaction_handler.cpp.

◆ clearLastMarkerPoses()

void robot_interaction::InteractionHandler::clearLastMarkerPoses ( )

Clear the last interactive_marker command poses for all end-effectors and joints.

Definition at line 181 of file interaction_handler.cpp.

◆ clearMenuHandler()

void robot_interaction::InteractionHandler::clearMenuHandler ( )

Remove the menu handler for this interaction handler.

Definition at line 199 of file interaction_handler.cpp.

◆ clearPoseOffset() [1/2]

void robot_interaction::InteractionHandler::clearPoseOffset ( const EndEffectorInteraction eef)

Clear the interactive marker pose offset for the given end-effector.

Parameters
Thetarget end-effector.

Definition at line 102 of file interaction_handler.cpp.

◆ clearPoseOffset() [2/2]

void robot_interaction::InteractionHandler::clearPoseOffset ( const JointInteraction vj)

Clear the interactive marker pose offset for the given joint.

Parameters
Thetarget joint.

Definition at line 108 of file interaction_handler.cpp.

◆ clearPoseOffsets()

void robot_interaction::InteractionHandler::clearPoseOffsets ( )

Clear the pose offset for all end-effectors and virtual joints.

Definition at line 114 of file interaction_handler.cpp.

◆ getControlsVisible()

bool robot_interaction::InteractionHandler::getControlsVisible ( ) const

Definition at line 456 of file interaction_handler.cpp.

◆ getLastEndEffectorMarkerPose()

bool robot_interaction::InteractionHandler::getLastEndEffectorMarkerPose ( const EndEffectorInteraction eef,
geometry_msgs::msg::PoseStamped &  pose 
)

Get the last interactive_marker command pose for an end-effector.

Parameters
Theend-effector in question.
APoseStamped 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.

Definition at line 144 of file interaction_handler.cpp.

◆ getLastJointMarkerPose()

bool robot_interaction::InteractionHandler::getLastJointMarkerPose ( const JointInteraction vj,
geometry_msgs::msg::PoseStamped &  pose 
)

Get the last interactive_marker command pose for a joint.

Parameters
Thejoint in question.
APoseStamped message containing the last (offset-removed) pose commanded for the joint.
Returns
True if a pose for that joint was found, false otherwise.

Definition at line 157 of file interaction_handler.cpp.

◆ getMenuHandler()

const std::shared_ptr< interactive_markers::MenuHandler > & robot_interaction::InteractionHandler::getMenuHandler ( )

Get the menu handler that defines menus and callbacks for all interactive markers drawn by this interaction handler.

Returns
The menu handler.

Definition at line 193 of file interaction_handler.cpp.

◆ getMeshesVisible()

bool robot_interaction::InteractionHandler::getMeshesVisible ( ) const

Definition at line 444 of file interaction_handler.cpp.

◆ getName()

const std::string & robot_interaction::InteractionHandler::getName ( ) const
inline

Definition at line 99 of file interaction_handler.h.

◆ getPoseOffset() [1/2]

bool robot_interaction::InteractionHandler::getPoseOffset ( const EndEffectorInteraction eef,
geometry_msgs::msg::Pose &  m 
)

Get the offset from EEF to its marker.

Parameters
Thetarget end-effector.
Thepose offset (only valid if return value is true).
Returns
True if an offset was found for the given end-effector.

Definition at line 120 of file interaction_handler.cpp.

Here is the caller graph for this function:

◆ getPoseOffset() [2/2]

bool robot_interaction::InteractionHandler::getPoseOffset ( const JointInteraction vj,
geometry_msgs::msg::Pose &  m 
)

Get the offset from a joint to its marker.

Parameters
vjThe joint.
mThe pose offset (only valid if return value is true).
Returns
True if an offset was found for the given joint.

Definition at line 132 of file interaction_handler.cpp.

◆ getState()

moveit::core::RobotStateConstPtr robot_interaction::LockedRobotState::getState ( ) const

Get a copy of the RobotState maintained by this InteractionHandler.

Definition at line 76 of file locked_robot_state.cpp.

◆ getUpdateCallback()

const InteractionHandlerCallbackFn & robot_interaction::InteractionHandler::getUpdateCallback ( ) const

Definition at line 432 of file interaction_handler.cpp.

◆ handleEndEffector()

void robot_interaction::InteractionHandler::handleEndEffector ( const EndEffectorInteraction eef,
const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr &  feedback 
)
virtual

Update the internal state maintained by the handler using information from the received feedback message.

Definition at line 222 of file interaction_handler.cpp.

Here is the call graph for this function:

◆ handleGeneric()

void robot_interaction::InteractionHandler::handleGeneric ( const GenericInteraction g,
const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr &  feedback 
)
virtual

Update the internal state maintained by the handler using information from the received feedback message.

Definition at line 205 of file interaction_handler.cpp.

Here is the call graph for this function:

◆ handleJoint()

void robot_interaction::InteractionHandler::handleJoint ( const JointInteraction vj,
const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr &  feedback 
)
virtual

Update the internal state maintained by the handler using information from the received feedback message.

Definition at line 255 of file interaction_handler.cpp.

Here is the call graph for this function:

◆ inError() [1/3]

bool robot_interaction::InteractionHandler::inError ( const EndEffectorInteraction eef) const
virtual

Check if the marker corresponding to this end-effector leads to an invalid state.

Definition at line 338 of file interaction_handler.cpp.

◆ inError() [2/3]

bool robot_interaction::InteractionHandler::inError ( const GenericInteraction g) const
virtual

Check if the generic marker to an invalid state.

Definition at line 343 of file interaction_handler.cpp.

◆ inError() [3/3]

bool robot_interaction::InteractionHandler::inError ( const JointInteraction vj) const
virtual

Check if the marker corresponding to this joint leads to an invalid state.

Definition at line 348 of file interaction_handler.cpp.

◆ setControlsVisible()

void robot_interaction::InteractionHandler::setControlsVisible ( bool  visible)

Definition at line 450 of file interaction_handler.cpp.

◆ setMenuHandler()

void robot_interaction::InteractionHandler::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 interaction handler.

Parameters
Amenu handler.

Definition at line 187 of file interaction_handler.cpp.

◆ setMeshesVisible()

void robot_interaction::InteractionHandler::setMeshesVisible ( bool  visible)

Definition at line 438 of file interaction_handler.cpp.

◆ setPoseOffset() [1/2]

void robot_interaction::InteractionHandler::setPoseOffset ( const EndEffectorInteraction eef,
const geometry_msgs::msg::Pose &  m 
)

Set the offset from EEF to its marker.

Parameters
eefThe target end-effector.
mThe pose of the marker in the frame of the end-effector parent.

Definition at line 90 of file interaction_handler.cpp.

◆ setPoseOffset() [2/2]

void robot_interaction::InteractionHandler::setPoseOffset ( const JointInteraction j,
const geometry_msgs::msg::Pose &  m 
)

Set the offset from a joint to its marker.

Parameters
jThe target joint.
mThe pose of the marker in the frame of the joint parent.

Definition at line 96 of file interaction_handler.cpp.

◆ setState()

void robot_interaction::LockedRobotState::setState ( const moveit::core::RobotState state)

Set a new RobotState for this InteractionHandler.

Definition at line 79 of file locked_robot_state.cpp.

◆ setUpdateCallback()

void robot_interaction::InteractionHandler::setUpdateCallback ( const InteractionHandlerCallbackFn callback)

Definition at line 426 of file interaction_handler.cpp.

◆ transformFeedbackPose()

bool robot_interaction::InteractionHandler::transformFeedbackPose ( const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr &  feedback,
const geometry_msgs::msg::Pose &  offset,
geometry_msgs::msg::PoseStamped &  tpose 
)
protected

Definition at line 386 of file interaction_handler.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ name_

const std::string robot_interaction::InteractionHandler::name_
protected

Definition at line 225 of file interaction_handler.h.

◆ planning_frame_

const std::string robot_interaction::InteractionHandler::planning_frame_
protected

Definition at line 226 of file interaction_handler.h.

◆ tf_buffer_

std::shared_ptr<tf2_ros::Buffer> robot_interaction::InteractionHandler::tf_buffer_
protected

Definition at line 227 of file interaction_handler.h.


The documentation for this class was generated from the following files: