Namespaces | Classes | Typedefs | Functions | Variables
robot_interaction Namespace Reference

Namespaces

namespace  InteractionStyle

Classes

struct  EndEffectorInteraction
struct  GenericInteraction
class  InteractionHandler
struct  JointInteraction
struct  KinematicOptions
class  KinematicOptionsMap
class  LockedRobotState
 Maintain a RobotState in a multithreaded environment. More...
class  RobotInteraction

Typedefs

typedef boost::function< void(InteractionHandler
*, bool) 
InteractionHandlerCallbackFn )
typedef boost::shared_ptr
< const InteractionHandler
InteractionHandlerConstPtr
typedef boost::shared_ptr
< InteractionHandler
InteractionHandlerPtr
typedef boost::function< bool(const
robot_state::RobotState &state,
visualization_msgs::InteractiveMarker
&marker)> 
InteractiveMarkerConstructorFn
typedef boost::function< bool(const
robot_state::RobotState
&, geometry_msgs::Pose &)> 
InteractiveMarkerUpdateFn
typedef boost::shared_ptr
< KinematicOptionsMap
KinematicOptionsMapPtr
typedef boost::shared_ptr
< const LockedRobotState
LockedRobotStateConstPtr
typedef boost::shared_ptr
< LockedRobotState
LockedRobotStatePtr
typedef boost::function< bool(robot_state::RobotState
&state, const
visualization_msgs::InteractiveMarkerFeedbackConstPtr
&feedback)> 
ProcessFeedbackFn
typedef boost::shared_ptr
< const RobotInteraction
RobotInteractionConstPtr
typedef boost::shared_ptr
< RobotInteraction
RobotInteractionPtr

Functions

void add6DOFControl (visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
void addErrorMarker (visualization_msgs::InteractiveMarker &im)
void addOrientationControl (visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
void addPlanarXYControl (visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
void addPositionControl (visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
void addTArrowMarker (visualization_msgs::InteractiveMarker &im)
void addViewPlaneControl (visualization_msgs::InteractiveMarker &int_marker, double radius, const std_msgs::ColorRGBA &color, bool position=true, bool orientation=true)
static std::string getMarkerName (const ::robot_interaction::InteractionHandlerPtr &handler, const EndEffectorInteraction &eef)
static std::string getMarkerName (const ::robot_interaction::InteractionHandlerPtr &handler, const JointInteraction &vj)
static std::string getMarkerName (const ::robot_interaction::InteractionHandlerPtr &handler, const GenericInteraction &g)
visualization_msgs::InteractiveMarker make6DOFMarker (const std::string &name, const geometry_msgs::PoseStamped &stamped, double scale, bool orientation_fixed=false)
visualization_msgs::InteractiveMarker makeEmptyInteractiveMarker (const std::string &name, const geometry_msgs::PoseStamped &stamped, double scale)
visualization_msgs::InteractiveMarker makePlanarXYMarker (const std::string &name, const geometry_msgs::PoseStamped &stamped, double scale, bool orientation_fixed=false)

Variables

static const float END_EFFECTOR_REACHABLE_COLOR [4] = { 0.2, 1.0, 0.2, 1.0 }
static const float END_EFFECTOR_UNREACHABLE_COLOR [4] = { 1.0, 0.3, 0.3, 1.0 }

Typedef Documentation

Function type for notifying client of RobotState changes.

This callback function is called by the InteractionHandler::handle* functions, when changes are made to the internal robot state the handler maintains. The handler passes its own pointer as argument to the callback, as well as a boolean flag that indicates whether the error state changed -- whether updates to the robot state performed in the InteractionHandler::handle* functions have switched from failing to succeeding or the other way around.

Definition at line 61 of file interaction_handler.h.

Definition at line 51 of file interaction_handler.h.

Definition at line 49 of file interaction_handler.h.

typedef boost::function<bool( const robot_state::RobotState& state, visualization_msgs::InteractiveMarker& marker)> robot_interaction::InteractiveMarkerConstructorFn

Type of function for constructing markers. This callback sets up the marker used for an interaction.

Parameters:
statethe current state of the robot
markerthe function should fill this in with an InteractiveMarker that will be used to control the interaction.
Returns:
true if the function succeeds, false if the function was not able to fill in marker.

Definition at line 102 of file interaction.h.

typedef boost::function<bool( const robot_state::RobotState&, geometry_msgs::Pose&)> robot_interaction::InteractiveMarkerUpdateFn

Type of function for updating marker pose for new state. This callback is called when the robot state has changed. Callback should calculate a new pose for the marker based on the passed in robot state.

Parameters:
statethe new state of the robot
posethe function should fill this in with the new pose of the marker, given the new state of the robot.
Returns:
true if the pose was modified, false if no update is needed (i.e. if the pose did not change).

Definition at line 132 of file interaction.h.

Definition at line 56 of file interaction_handler.h.

Definition at line 111 of file locked_robot_state.h.

Definition at line 110 of file locked_robot_state.h.

typedef boost::function<bool( robot_state::RobotState& state, const visualization_msgs::InteractiveMarkerFeedbackConstPtr & feedback)> robot_interaction::ProcessFeedbackFn

Type of function for processing marker feedback. This callback function handles feedback for an Interaction's marker. Callback should update the robot state that was passed in according to the new position of the marker.

Parameters:
statethe current state of the robot
markerthe function should fill this in with an InteractiveMarker that will be used to control the interaction.
Returns:
false if the state was not successfully updated or the new state is somehow invalid or erronious (e.g. in collision). true if everything worked well.

Definition at line 118 of file interaction.h.

Definition at line 310 of file robot_interaction.h.

Definition at line 53 of file interaction_handler.h.


Function Documentation

void robot_interaction::add6DOFControl ( visualization_msgs::InteractiveMarker &  int_marker,
bool  orientation_fixed = false 
)

Definition at line 168 of file interactive_marker_helpers.cpp.

void robot_interaction::addErrorMarker ( visualization_msgs::InteractiveMarker &  im)

Definition at line 111 of file interactive_marker_helpers.cpp.

void robot_interaction::addOrientationControl ( visualization_msgs::InteractiveMarker &  int_marker,
bool  orientation_fixed = false 
)

Definition at line 174 of file interactive_marker_helpers.cpp.

void robot_interaction::addPlanarXYControl ( visualization_msgs::InteractiveMarker &  int_marker,
bool  orientation_fixed = false 
)

Definition at line 140 of file interactive_marker_helpers.cpp.

void robot_interaction::addPositionControl ( visualization_msgs::InteractiveMarker &  int_marker,
bool  orientation_fixed = false 
)

Definition at line 202 of file interactive_marker_helpers.cpp.

void robot_interaction::addTArrowMarker ( visualization_msgs::InteractiveMarker &  im)

Definition at line 57 of file interactive_marker_helpers.cpp.

void robot_interaction::addViewPlaneControl ( visualization_msgs::InteractiveMarker &  int_marker,
double  radius,
const std_msgs::ColorRGBA &  color,
bool  position = true,
bool  orientation = true 
)

Definition at line 230 of file interactive_marker_helpers.cpp.

static std::string robot_interaction::getMarkerName ( const ::robot_interaction::InteractionHandlerPtr handler,
const EndEffectorInteraction &  eef 
) [inline, static]

Definition at line 426 of file robot_interaction.cpp.

static std::string robot_interaction::getMarkerName ( const ::robot_interaction::InteractionHandlerPtr handler,
const JointInteraction &  vj 
) [inline, static]

Definition at line 433 of file robot_interaction.cpp.

static std::string robot_interaction::getMarkerName ( const ::robot_interaction::InteractionHandlerPtr handler,
const GenericInteraction &  g 
) [inline, static]

Definition at line 440 of file robot_interaction.cpp.

visualization_msgs::InteractiveMarker robot_interaction::make6DOFMarker ( const std::string &  name,
const geometry_msgs::PoseStamped &  stamped,
double  scale,
bool  orientation_fixed = false 
)

Definition at line 267 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker robot_interaction::makeEmptyInteractiveMarker ( const std::string &  name,
const geometry_msgs::PoseStamped &  stamped,
double  scale 
)

Definition at line 45 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker robot_interaction::makePlanarXYMarker ( const std::string &  name,
const geometry_msgs::PoseStamped &  stamped,
double  scale,
bool  orientation_fixed = false 
)

Definition at line 257 of file interactive_marker_helpers.cpp.


Variable Documentation

const float robot_interaction::END_EFFECTOR_REACHABLE_COLOR[4] = { 0.2, 1.0, 0.2, 1.0 } [static]

Definition at line 61 of file robot_interaction.cpp.

const float robot_interaction::END_EFFECTOR_UNREACHABLE_COLOR[4] = { 1.0, 0.3, 0.3, 1.0 } [static]

Definition at line 60 of file robot_interaction.cpp.



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