Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
robot_interaction::InteractionHandler Class Reference

#include <interaction_handler.h>

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

Public Member Functions

void clearError (void)
 Clear any error settings. This makes the markers appear as if the state is no longer invalid. More...
 
void clearLastEndEffectorMarkerPose (const EndEffectorInteraction &eef)
 Clear the last interactive_marker command pose for the given end-effector. More...
 
void clearLastJointMarkerPose (const JointInteraction &vj)
 Clear the last interactive_marker command pose for the given joint. More...
 
void clearLastMarkerPoses ()
 Clear the last interactive_marker command poses for all end-effectors and joints. More...
 
void clearMenuHandler ()
 Remove the menu handler for this interaction handler. More...
 
void clearPoseOffset (const EndEffectorInteraction &eef)
 Clear the interactive marker pose offset for the given end-effector. More...
 
void clearPoseOffset (const JointInteraction &vj)
 Clear the interactive marker pose offset for the given joint. More...
 
void clearPoseOffsets ()
 Clear the pose offset for all end-effectors and virtual joints. More...
 
bool getControlsVisible () const
 
kinematics::KinematicsQueryOptions getKinematicsQueryOptions () const
 
bool getLastEndEffectorMarkerPose (const EndEffectorInteraction &eef, geometry_msgs::PoseStamped &pose)
 Get the last interactive_marker command pose for an end-effector. More...
 
bool getLastJointMarkerPose (const JointInteraction &vj, geometry_msgs::PoseStamped &pose)
 Get the last interactive_marker command pose for a joint. More...
 
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. More...
 
bool getMeshesVisible () const
 
const std::string & getName () const
 
bool getPoseOffset (const EndEffectorInteraction &eef, geometry_msgs::Pose &m)
 Get the offset from EEF to its marker. More...
 
bool getPoseOffset (const JointInteraction &vj, geometry_msgs::Pose &m)
 Get the offset from a joint to its marker. More...
 
const InteractionHandlerCallbackFngetUpdateCallback () const
 
virtual void handleEndEffector (const EndEffectorInteraction &eef, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Update the internal state maintained by the handler using information from the received feedback message. More...
 
virtual void handleGeneric (const GenericInteraction &g, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Update the internal state maintained by the handler using information from the received feedback message. More...
 
virtual void handleJoint (const JointInteraction &vj, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Update the internal state maintained by the handler using information from the received feedback message. More...
 
virtual bool inError (const EndEffectorInteraction &eef) const
 Check if the marker corresponding to this end-effector leads to an invalid state. More...
 
virtual bool inError (const JointInteraction &vj) const
 Check if the marker corresponding to this joint leads to an invalid state. More...
 
virtual bool inError (const GenericInteraction &g) const
 Check if the generic marker to an invalid state. More...
 
 InteractionHandler (const RobotInteractionPtr &robot_interaction, const std::string &name, const robot_state::RobotState &initial_robot_state, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >())
 
 InteractionHandler (const RobotInteractionPtr &robot_interaction, const std::string &name, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >())
 
 InteractionHandler (const std::string &name, const robot_state::RobotState &initial_robot_state, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >())
 
 InteractionHandler (const std::string &name, const robot_model::RobotModelConstPtr &model, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >())
 
void setControlsVisible (bool visible)
 
void setGroupStateValidityCallback (const robot_state::GroupStateValidityCallbackFn &callback)
 
void setIKAttempts (unsigned int attempts)
 
void setIKTimeout (double timeout)
 
void setKinematicsQueryOptions (const kinematics::KinematicsQueryOptions &opt)
 
void setKinematicsQueryOptionsForGroup (const std::string &group_name, const kinematics::KinematicsQueryOptions &options)
 
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. More...
 
void setMeshesVisible (bool visible)
 
void setPoseOffset (const EndEffectorInteraction &eef, const geometry_msgs::Pose &m)
 Set the offset from EEF to its marker. More...
 
void setPoseOffset (const JointInteraction &j, const geometry_msgs::Pose &m)
 Set the offset from a joint to its marker. More...
 
void setRobotInteraction (RobotInteraction *robot_interaction)
 This should only be called by RobotInteraction. Associates this InteractionHandler to a RobotInteraction. More...
 
void setUpdateCallback (const InteractionHandlerCallbackFn &callback)
 
virtual ~InteractionHandler ()
 
- Public Member Functions inherited from robot_interaction::LockedRobotState
robot_state::RobotStateConstPtr getState () const
 get read-only access to the state. More...
 
 LockedRobotState (const robot_state::RobotState &state)
 
 LockedRobotState (const robot_model::RobotModelPtr &model)
 
void modifyState (const ModifyStateFunction &modify)
 
void setState (const robot_state::RobotState &state)
 Set the state to the new value. More...
 
virtual ~LockedRobotState ()
 

Protected Member Functions

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

Protected Attributes

const std::string name_
 
const std::string planning_frame_
 
boost::shared_ptr< tf::Transformertf_
 
- Protected Attributes inherited from robot_interaction::LockedRobotState
boost::mutex state_lock_
 

Private Types

typedef boost::function< void(InteractionHandler *)> StateChangeCallbackFn
 

Private Member Functions

bool getErrorState (const std::string &name) const
 
bool setErrorState (const std::string &name, bool new_error_state)
 
void updateStateEndEffector (robot_state::RobotState *state, const EndEffectorInteraction *eef, const geometry_msgs::Pose *pose, StateChangeCallbackFn *callback)
 
void updateStateGeneric (robot_state::RobotState *state, const GenericInteraction *g, const visualization_msgs::InteractiveMarkerFeedbackConstPtr *feedback, StateChangeCallbackFn *callback)
 
void updateStateJoint (robot_state::RobotState *state, const JointInteraction *vj, const geometry_msgs::Pose *pose, StateChangeCallbackFn *callback)
 

Static Private Member Functions

static std::string fixName (std::string name)
 

Private Attributes

bool display_controls_
 
bool display_meshes_
 
std::set< std::string > error_state_
 
KinematicOptionsMapPtr kinematic_options_map_
 
std::shared_ptr< interactive_markers::MenuHandlermenu_handler_
 
std::map< std::string, geometry_msgs::Poseoffset_map_
 
boost::mutex offset_map_lock_
 
std::map< std::string, geometry_msgs::PoseStamped > pose_map_
 
boost::mutex pose_map_lock_
 
const void * robot_interaction_
 
boost::function< void(InteractionHandler *handler, bool error_state_changed)> update_callback_
 

Additional Inherited Members

- Public Types inherited from robot_interaction::LockedRobotState
typedef boost::function< void(robot_state::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.

Member Typedef Documentation

Definition at line 235 of file interaction_handler.h.

Constructor & Destructor Documentation

robot_interaction::InteractionHandler::InteractionHandler ( const RobotInteractionPtr &  robot_interaction,
const std::string &  name,
const robot_state::RobotState &  initial_robot_state,
const boost::shared_ptr< tf::Transformer > &  tf = boost::shared_ptr<tf::Transformer>() 
)

Definition at line 57 of file interaction_handler.cpp.

robot_interaction::InteractionHandler::InteractionHandler ( const RobotInteractionPtr &  robot_interaction,
const std::string &  name,
const boost::shared_ptr< tf::Transformer > &  tf = boost::shared_ptr<tf::Transformer>() 
)

Definition at line 72 of file interaction_handler.cpp.

robot_interaction::InteractionHandler::InteractionHandler ( const std::string &  name,
const robot_state::RobotState &  initial_robot_state,
const boost::shared_ptr< tf::Transformer > &  tf = boost::shared_ptr<tf::Transformer>() 
)

Definition at line 87 of file interaction_handler.cpp.

robot_interaction::InteractionHandler::InteractionHandler ( const std::string &  name,
const robot_model::RobotModelConstPtr &  model,
const boost::shared_ptr< tf::Transformer > &  tf = boost::shared_ptr<tf::Transformer>() 
)

Definition at line 101 of file interaction_handler.cpp.

virtual robot_interaction::InteractionHandler::~InteractionHandler ( )
inlinevirtual

Definition at line 95 of file interaction_handler.h.

Member Function Documentation

void robot_interaction::InteractionHandler::clearError ( void  )

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

Definition at line 369 of file interaction_handler.cpp.

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 198 of file interaction_handler.cpp.

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 204 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::clearLastMarkerPoses ( )

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

Definition at line 210 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::clearMenuHandler ( )

Remove the menu handler for this interaction handler.

Definition at line 228 of file interaction_handler.cpp.

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 132 of file interaction_handler.cpp.

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

Clear the interactive marker pose offset for the given joint.

Parameters
Thetarget joint.

Definition at line 138 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::clearPoseOffsets ( )

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

Definition at line 144 of file interaction_handler.cpp.

std::string robot_interaction::InteractionHandler::fixName ( std::string  name)
staticprivate

Definition at line 114 of file interaction_handler.cpp.

bool robot_interaction::InteractionHandler::getControlsVisible ( ) const

Definition at line 564 of file interaction_handler.cpp.

bool robot_interaction::InteractionHandler::getErrorState ( const std::string &  name) const
private

Get the error state for name. True if Interaction name is not in a valid pose.

Definition at line 392 of file interaction_handler.cpp.

kinematics::KinematicsQueryOptions robot_interaction::InteractionHandler::getKinematicsQueryOptions ( ) const

Definition at line 528 of file interaction_handler.cpp.

bool robot_interaction::InteractionHandler::getLastEndEffectorMarkerPose ( const EndEffectorInteraction eef,
geometry_msgs::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 174 of file interaction_handler.cpp.

bool robot_interaction::InteractionHandler::getLastJointMarkerPose ( const JointInteraction vj,
geometry_msgs::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 186 of file interaction_handler.cpp.

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 222 of file interaction_handler.cpp.

bool robot_interaction::InteractionHandler::getMeshesVisible ( ) const

Definition at line 552 of file interaction_handler.cpp.

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

Definition at line 99 of file interaction_handler.h.

bool robot_interaction::InteractionHandler::getPoseOffset ( const EndEffectorInteraction eef,
geometry_msgs::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 150 of file interaction_handler.cpp.

bool robot_interaction::InteractionHandler::getPoseOffset ( const JointInteraction vj,
geometry_msgs::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 162 of file interaction_handler.cpp.

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

Definition at line 540 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::handleEndEffector ( const EndEffectorInteraction eef,
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback 
)
virtual

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

Definition at line 250 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::handleGeneric ( const GenericInteraction g,
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback 
)
virtual

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

Definition at line 234 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::handleJoint ( const JointInteraction vj,
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback 
)
virtual

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

Definition at line 281 of file interaction_handler.cpp.

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 354 of file interaction_handler.cpp.

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 364 of file interaction_handler.cpp.

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

Check if the generic marker to an invalid state.

Definition at line 359 of file interaction_handler.cpp.

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

Definition at line 558 of file interaction_handler.cpp.

bool robot_interaction::InteractionHandler::setErrorState ( const std::string &  name,
bool  new_error_state 
)
private

Definition at line 377 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::setGroupStateValidityCallback ( const robot_state::GroupStateValidityCallbackFn callback)

Definition at line 519 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::setIKAttempts ( unsigned int  attempts)

Definition at line 491 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::setIKTimeout ( double  timeout)

Definition at line 482 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::setKinematicsQueryOptions ( const kinematics::KinematicsQueryOptions opt)

Definition at line 500 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::setKinematicsQueryOptionsForGroup ( const std::string &  group_name,
const kinematics::KinematicsQueryOptions options 
)

Definition at line 509 of file interaction_handler.cpp.

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 216 of file interaction_handler.cpp.

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

Definition at line 546 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::setPoseOffset ( const EndEffectorInteraction eef,
const geometry_msgs::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 120 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::setPoseOffset ( const JointInteraction j,
const geometry_msgs::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 126 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::setRobotInteraction ( RobotInteraction robot_interaction)

This should only be called by RobotInteraction. Associates this InteractionHandler to a RobotInteraction.

Definition at line 444 of file interaction_handler.cpp.

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

Definition at line 534 of file interaction_handler.cpp.

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

Definition at line 398 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::updateStateEndEffector ( robot_state::RobotState *  state,
const EndEffectorInteraction eef,
const geometry_msgs::Pose pose,
StateChangeCallbackFn callback 
)
private

Definition at line 324 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::updateStateGeneric ( robot_state::RobotState *  state,
const GenericInteraction g,
const visualization_msgs::InteractiveMarkerFeedbackConstPtr *  feedback,
StateChangeCallbackFn callback 
)
private

Definition at line 313 of file interaction_handler.cpp.

void robot_interaction::InteractionHandler::updateStateJoint ( robot_state::RobotState *  state,
const JointInteraction vj,
const geometry_msgs::Pose pose,
StateChangeCallbackFn callback 
)
private

Definition at line 338 of file interaction_handler.cpp.

Member Data Documentation

bool robot_interaction::InteractionHandler::display_controls_
private

Definition at line 322 of file interaction_handler.h.

bool robot_interaction::InteractionHandler::display_meshes_
private

Definition at line 319 of file interaction_handler.h.

std::set<std::string> robot_interaction::InteractionHandler::error_state_
private

Definition at line 299 of file interaction_handler.h.

KinematicOptionsMapPtr robot_interaction::InteractionHandler::kinematic_options_map_
private

Definition at line 295 of file interaction_handler.h.

std::shared_ptr<interactive_markers::MenuHandler> robot_interaction::InteractionHandler::menu_handler_
private

Definition at line 306 of file interaction_handler.h.

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

Definition at line 230 of file interaction_handler.h.

std::map<std::string, geometry_msgs::Pose> robot_interaction::InteractionHandler::offset_map_
private

Definition at line 269 of file interaction_handler.h.

boost::mutex robot_interaction::InteractionHandler::offset_map_lock_
private

Definition at line 290 of file interaction_handler.h.

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

Definition at line 231 of file interaction_handler.h.

std::map<std::string, geometry_msgs::PoseStamped> robot_interaction::InteractionHandler::pose_map_
private

Definition at line 278 of file interaction_handler.h.

boost::mutex robot_interaction::InteractionHandler::pose_map_lock_
private

Definition at line 289 of file interaction_handler.h.

const void* robot_interaction::InteractionHandler::robot_interaction_
private

Definition at line 287 of file interaction_handler.h.

boost::shared_ptr<tf::Transformer> robot_interaction::InteractionHandler::tf_
protected

Definition at line 232 of file interaction_handler.h.

boost::function<void(InteractionHandler* handler, bool error_state_changed)> robot_interaction::InteractionHandler::update_callback_
private

Definition at line 316 of file interaction_handler.h.


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


robot_interaction
Author(s): Ioan Sucan
autogenerated on Sun Oct 18 2020 13:18:32