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

#include <robot_interaction.h>

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 RobotInteraction::EndEffector &eef)
 Clear the last interactive_marker command pose for the given end-effector.
void clearLastJointMarkerPose (const RobotInteraction::Joint &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 RobotInteraction::EndEffector &eef)
 Clear the interactive marker pose offset for the given end-effector.
void clearPoseOffset (const RobotInteraction::Joint &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
unsigned int getIKAttempts () const
double getIKTimeout () const
const
kinematics::KinematicsQueryOptions
getKinematicsQueryOptions () const
bool getLastEndEffectorMarkerPose (const RobotInteraction::EndEffector &eef, geometry_msgs::PoseStamped &pose)
 Get the last interactive_marker command pose for an end-effector.
bool getLastJointMarkerPose (const RobotInteraction::Joint &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 RobotInteraction::EndEffector &eef, geometry_msgs::Pose &m)
 Get the offset for the interactive marker controls for an end-effector, expressed in the frame of the end-effector parent.
bool getPoseOffset (const RobotInteraction::Joint &vj, geometry_msgs::Pose &m)
 Get the offset for the interactive marker controls for a joint, expressed in the frame of the joint parent.
robot_state::RobotStateConstPtr getState () const
const
robot_state::StateValidityCallbackFn
getStateValidityCallback () const
const
InteractionHandlerCallbackFn
getUpdateCallback () const
virtual void handleEndEffector (const RobotInteraction::EndEffector &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 RobotInteraction::Generic &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 RobotInteraction::Joint &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 RobotInteraction::EndEffector &eef) const
 Check if the marker corresponding to this end-effector leads to an invalid state.
virtual bool inError (const RobotInteraction::Joint &vj) const
 Check if the marker corresponding to this joint leads to an invalid state.
virtual bool inError (const RobotInteraction::Generic &g) const
 Check if the generic marker to an invalid state.
 InteractionHandler (const std::string &name, const robot_state::RobotState &kstate, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >())
 InteractionHandler (const std::string &name, const robot_model::RobotModelConstPtr &kmodel, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >())
void setControlsVisible (bool visible)
void setIKAttempts (unsigned int attempts)
void setIKTimeout (double timeout)
void setKinematicsQueryOptions (const kinematics::KinematicsQueryOptions &opt)
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 RobotInteraction::EndEffector &eef, const geometry_msgs::Pose &m)
 Set the offset for drawing the interactive marker controls for an end-effector, expressed in the frame of the end-effector parent.
void setPoseOffset (const RobotInteraction::Joint &eef, const geometry_msgs::Pose &m)
 Set the offset for drawing the interactive marker controls for a joint, expressed in the frame of the joint parent.
void setState (const robot_state::RobotState &kstate)
void setStateValidityCallback (const robot_state::StateValidityCallbackFn &callback)
void setUpdateCallback (const InteractionHandlerCallbackFn &callback)
virtual ~InteractionHandler ()

Protected Member Functions

robot_state::RobotStatePtr getUniqueStateAccess ()
void setStateToAccess (robot_state::RobotStatePtr &state)
bool transformFeedbackPose (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, const geometry_msgs::Pose &offset, geometry_msgs::PoseStamped &tpose)

Protected Attributes

bool display_controls_
bool display_meshes_
std::set< std::string > error_state_
unsigned int ik_attempts_
double ik_timeout_
kinematics::KinematicsQueryOptions kinematics_query_options_
robot_state::RobotStatePtr kstate_
boost::shared_ptr
< interactive_markers::MenuHandler
menu_handler_
std::string name_
std::map< std::string,
geometry_msgs::Pose
offset_map_
std::string planning_frame_
std::map< std::string,
geometry_msgs::PoseStamped > 
pose_map_
robot_state::StateValidityCallbackFn state_validity_callback_fn_
boost::shared_ptr
< tf::Transformer
tf_
boost::function< void(InteractionHandler
*handler, bool
error_state_changed) 
update_callback_ )

Private Member Functions

void setup ()

Private Attributes

boost::mutex offset_map_lock_
boost::mutex pose_map_lock_
boost::condition_variable state_available_condition_
boost::mutex state_lock_

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 174 of file robot_interaction.h.


Constructor & Destructor Documentation

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

Definition at line 57 of file robot_interaction.cpp.

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

Definition at line 69 of file robot_interaction.cpp.

Definition at line 185 of file robot_interaction.h.


Member Function Documentation

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

Definition at line 380 of file robot_interaction.cpp.

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

Parameters:
Thetarget end-effector.

Definition at line 167 of file robot_interaction.cpp.

Clear the last interactive_marker command pose for the given joint.

Parameters:
Thetarget joint.

Definition at line 173 of file robot_interaction.cpp.

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

Definition at line 179 of file robot_interaction.cpp.

Remove the menu handler for this interaction handler.

Definition at line 195 of file robot_interaction.cpp.

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

Parameters:
Thetarget end-effector.

Definition at line 101 of file robot_interaction.cpp.

Clear the interactive marker pose offset for the given joint.

Parameters:
Thetarget joint.

Definition at line 107 of file robot_interaction.cpp.

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

Definition at line 113 of file robot_interaction.cpp.

Definition at line 262 of file robot_interaction.h.

Definition at line 232 of file robot_interaction.h.

Definition at line 222 of file robot_interaction.h.

Definition at line 237 of file robot_interaction.h.

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 143 of file robot_interaction.cpp.

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 155 of file robot_interaction.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 190 of file robot_interaction.cpp.

Definition at line 252 of file robot_interaction.h.

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

Definition at line 189 of file robot_interaction.h.

Get the offset for the interactive marker controls for an end-effector, expressed in the frame of the end-effector parent.

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, false otherwise.

Definition at line 119 of file robot_interaction.cpp.

Get the offset for the interactive marker controls for a joint, expressed in the frame of the joint parent.

Parameters:
Thetarget joint.
Thepose offset (only valid if return value is true).
Returns:
True if an offset was found for the given joint, false otherwise.

Definition at line 131 of file robot_interaction.cpp.

Definition at line 200 of file robot_interaction.cpp.

Definition at line 212 of file robot_interaction.h.

Definition at line 231 of file robot_interaction.cpp.

Definition at line 202 of file robot_interaction.h.

void robot_interaction::RobotInteraction::InteractionHandler::handleEndEffector ( const RobotInteraction::EndEffector 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 283 of file robot_interaction.cpp.

void robot_interaction::RobotInteraction::InteractionHandler::handleGeneric ( const RobotInteraction::Generic 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 258 of file robot_interaction.cpp.

void robot_interaction::RobotInteraction::InteractionHandler::handleJoint ( const RobotInteraction::Joint 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 322 of file robot_interaction.cpp.

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

Definition at line 365 of file robot_interaction.cpp.

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

Definition at line 375 of file robot_interaction.cpp.

Check if the generic marker to an invalid state.

Definition at line 370 of file robot_interaction.cpp.

Definition at line 257 of file robot_interaction.h.

Definition at line 227 of file robot_interaction.h.

Definition at line 217 of file robot_interaction.h.

Definition at line 242 of file robot_interaction.h.

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

Parameters:
Amenu handler.

Definition at line 185 of file robot_interaction.cpp.

Definition at line 247 of file robot_interaction.h.

Set the offset for drawing the interactive marker controls for an end-effector, expressed in the frame of the end-effector parent.

Parameters:
Thetarget end-effector.
Thedesired pose offset.

Definition at line 89 of file robot_interaction.cpp.

Set the offset for drawing the interactive marker controls for a joint, expressed in the frame of the joint parent.

Parameters:
Thetarget joint.
Thedesired pose offset.

Definition at line 95 of file robot_interaction.cpp.

Definition at line 215 of file robot_interaction.cpp.

Definition at line 250 of file robot_interaction.cpp.

Definition at line 207 of file robot_interaction.h.

Definition at line 81 of file robot_interaction.cpp.

Definition at line 197 of file robot_interaction.h.

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

Definition at line 385 of file robot_interaction.cpp.


Member Data Documentation

Definition at line 416 of file robot_interaction.h.

Definition at line 415 of file robot_interaction.h.

Definition at line 381 of file robot_interaction.h.

Definition at line 410 of file robot_interaction.h.

Definition at line 409 of file robot_interaction.h.

Definition at line 413 of file robot_interaction.h.

Definition at line 379 of file robot_interaction.h.

Definition at line 401 of file robot_interaction.h.

Definition at line 377 of file robot_interaction.h.

Definition at line 389 of file robot_interaction.h.

Definition at line 423 of file robot_interaction.h.

Definition at line 378 of file robot_interaction.h.

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

Definition at line 397 of file robot_interaction.h.

Definition at line 422 of file robot_interaction.h.

Definition at line 421 of file robot_interaction.h.

Definition at line 420 of file robot_interaction.h.

Definition at line 408 of file robot_interaction.h.

Definition at line 380 of file robot_interaction.h.

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

Definition at line 406 of file robot_interaction.h.


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


robot_interaction
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 02:33:46