Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes
robot_interaction::InteractionHandler Class Reference

#include <interaction_handler.h>

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

List of all members.

Public Member Functions

void clearError (void)
 Clear any error settings. This makes the markers appear as if the state is no longer invalid.
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.
void clearMenuHandler ()
 Remove the menu handler for this interaction handler.
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.
bool getControlsVisible () const
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.
bool getLastJointMarkerPose (const JointInteraction &vj, geometry_msgs::PoseStamped &pose)
 Get the last interactive_marker command pose for a joint.
const boost::shared_ptr
< interactive_markers::MenuHandler > & 
getMenuHandler ()
 Get the menu handler that defines menus and callbacks for all interactive markers drawn by this interaction handler.
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.
bool getPoseOffset (const JointInteraction &vj, geometry_msgs::Pose &m)
 Get the offset from a joint to its marker.
const
InteractionHandlerCallbackFn
getUpdateCallback () 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.
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.
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.
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.
 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 boost::shared_ptr< interactive_markers::MenuHandler > &mh)
 Set the menu handler that defines menus and callbacks for all interactive markers drawn by this interaction handler.
void setMeshesVisible (bool visible)
void setPoseOffset (const EndEffectorInteraction &eef, const geometry_msgs::Pose &m)
 Set the offset from EEF to its marker.
void setPoseOffset (const JointInteraction &j, const geometry_msgs::Pose &m)
 Set the offset from a joint to its marker.
void setRobotInteraction (RobotInteraction *robot_interaction)
 This should only be called by RobotInteraction. Associates this InteractionHandler to a RobotInteraction.
void setUpdateCallback (const InteractionHandlerCallbackFn &callback)
virtual ~InteractionHandler ()

Protected Member Functions

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

Protected Attributes

const std::string name_
const std::string planning_frame_
boost::shared_ptr
< tf::Transformer
tf_

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_
boost::shared_ptr
< interactive_markers::MenuHandler
menu_handler_
std::map< std::string,
geometry_msgs::Pose
offset_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_ )

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 85 of file interaction_handler.h.


Member Typedef Documentation

Definition at line 259 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 58 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 75 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 92 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 108 of file interaction_handler.cpp.

Definition at line 108 of file interaction_handler.h.


Member Function Documentation

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

Definition at line 434 of file interaction_handler.cpp.

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

Parameters:
Thetarget end-effector.

Definition at line 207 of file interaction_handler.cpp.

Clear the last interactive_marker command pose for the given joint.

Parameters:
Thetarget joint.

Definition at line 213 of file interaction_handler.cpp.

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

Definition at line 219 of file interaction_handler.cpp.

Remove the menu handler for this interaction handler.

Definition at line 237 of file interaction_handler.cpp.

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

Parameters:
Thetarget end-effector.

Definition at line 141 of file interaction_handler.cpp.

Clear the interactive marker pose offset for the given joint.

Parameters:
Thetarget joint.

Definition at line 147 of file interaction_handler.cpp.

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

Definition at line 153 of file interaction_handler.cpp.

std::string robot_interaction::InteractionHandler::fixName ( std::string  name) [static, private]

Definition at line 123 of file interaction_handler.cpp.

Definition at line 648 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 457 of file interaction_handler.cpp.

Definition at line 611 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 183 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 195 of file interaction_handler.cpp.

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

Definition at line 636 of file interaction_handler.cpp.

const std::string& robot_interaction::InteractionHandler::getName ( void  ) const [inline]

Definition at line 112 of file interaction_handler.h.

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

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

Definition at line 624 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 265 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 244 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 301 of file interaction_handler.cpp.

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

Definition at line 419 of file interaction_handler.cpp.

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

Definition at line 429 of file interaction_handler.cpp.

Check if the generic marker to an invalid state.

Definition at line 424 of file interaction_handler.cpp.

Definition at line 642 of file interaction_handler.cpp.

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

Definition at line 442 of file interaction_handler.cpp.

Definition at line 599 of file interaction_handler.cpp.

Definition at line 563 of file interaction_handler.cpp.

Definition at line 552 of file interaction_handler.cpp.

Definition at line 574 of file interaction_handler.cpp.

Definition at line 586 of file interaction_handler.cpp.

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

Parameters:
Amenu handler.

Definition at line 225 of file interaction_handler.cpp.

Definition at line 630 of file interaction_handler.cpp.

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

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

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

Definition at line 513 of file interaction_handler.cpp.

Definition at line 618 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 464 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 353 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 338 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 375 of file interaction_handler.cpp.


Member Data Documentation

Definition at line 353 of file interaction_handler.h.

Definition at line 350 of file interaction_handler.h.

Definition at line 329 of file interaction_handler.h.

Definition at line 325 of file interaction_handler.h.

Definition at line 336 of file interaction_handler.h.

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

Definition at line 253 of file interaction_handler.h.

Definition at line 299 of file interaction_handler.h.

Definition at line 320 of file interaction_handler.h.

Definition at line 254 of file interaction_handler.h.

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

Definition at line 308 of file interaction_handler.h.

Definition at line 319 of file interaction_handler.h.

Definition at line 317 of file interaction_handler.h.

Definition at line 255 of file interaction_handler.h.

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

Definition at line 347 of file interaction_handler.h.


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


robot_interaction
Author(s): Ioan Sucan
autogenerated on Wed Aug 26 2015 12:44:19