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

Namespaces

 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::function< bool(const moveit::core::RobotState &state, visualization_msgs::InteractiveMarker &marker)> InteractiveMarkerConstructorFn
 
typedef boost::function< bool(const moveit::core::RobotState &, geometry_msgs::Pose &)> InteractiveMarkerUpdateFn
 
typedef boost::function< bool(moveit::core::RobotState &state, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)> ProcessFeedbackFn
 

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 InteractionHandlerPtr &handler, const EndEffectorInteraction &eef)
 
static std::string getMarkerName (const InteractionHandlerPtr &handler, const GenericInteraction &g)
 
static std::string getMarkerName (const InteractionHandlerPtr &handler, const JointInteraction &vj)
 
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)
 
 MOVEIT_CLASS_FORWARD (InteractionHandler)
 
 MOVEIT_CLASS_FORWARD (KinematicOptionsMap)
 
 MOVEIT_CLASS_FORWARD (LockedRobotState)
 
 MOVEIT_CLASS_FORWARD (RobotInteraction)
 

Variables

static const double DEFAULT_SCALE = 0.25
 
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 }
 
static const double SQRT2INV = 0.707106781
 

Typedef Documentation

◆ InteractionHandlerCallbackFn

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

◆ InteractiveMarkerConstructorFn

typedef boost::function<bool(const moveit::core::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 88 of file interaction.h.

◆ InteractiveMarkerUpdateFn

typedef boost::function<bool(const moveit::core::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 114 of file interaction.h.

◆ ProcessFeedbackFn

typedef boost::function<bool(moveit::core::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 103 of file interaction.h.

Function Documentation

◆ add6DOFControl()

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

Definition at line 204 of file interactive_marker_helpers.cpp.

◆ addErrorMarker()

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

Definition at line 144 of file interactive_marker_helpers.cpp.

◆ addOrientationControl()

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

Definition at line 210 of file interactive_marker_helpers.cpp.

◆ addPlanarXYControl()

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

Definition at line 176 of file interactive_marker_helpers.cpp.

◆ addPositionControl()

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

Definition at line 238 of file interactive_marker_helpers.cpp.

◆ addTArrowMarker()

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

Definition at line 88 of file interactive_marker_helpers.cpp.

◆ addViewPlaneControl()

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 266 of file interactive_marker_helpers.cpp.

◆ getMarkerName() [1/3]

static std::string robot_interaction::getMarkerName ( const InteractionHandlerPtr &  handler,
const EndEffectorInteraction eef 
)
inlinestatic

Definition at line 467 of file robot_interaction.cpp.

◆ getMarkerName() [2/3]

static std::string robot_interaction::getMarkerName ( const InteractionHandlerPtr &  handler,
const GenericInteraction g 
)
inlinestatic

Definition at line 477 of file robot_interaction.cpp.

◆ getMarkerName() [3/3]

static std::string robot_interaction::getMarkerName ( const InteractionHandlerPtr &  handler,
const JointInteraction vj 
)
inlinestatic

Definition at line 472 of file robot_interaction.cpp.

◆ make6DOFMarker()

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

Definition at line 303 of file interactive_marker_helpers.cpp.

◆ makeEmptyInteractiveMarker()

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

Definition at line 78 of file interactive_marker_helpers.cpp.

◆ makePlanarXYMarker()

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

Definition at line 294 of file interactive_marker_helpers.cpp.

◆ MOVEIT_CLASS_FORWARD() [1/4]

robot_interaction::MOVEIT_CLASS_FORWARD ( InteractionHandler  )

◆ MOVEIT_CLASS_FORWARD() [2/4]

robot_interaction::MOVEIT_CLASS_FORWARD ( KinematicOptionsMap  )

◆ MOVEIT_CLASS_FORWARD() [3/4]

robot_interaction::MOVEIT_CLASS_FORWARD ( LockedRobotState  )

◆ MOVEIT_CLASS_FORWARD() [4/4]

robot_interaction::MOVEIT_CLASS_FORWARD ( RobotInteraction  )

Variable Documentation

◆ DEFAULT_SCALE

const double robot_interaction::DEFAULT_SCALE = 0.25
static

Definition at line 149 of file robot_interaction.cpp.

◆ END_EFFECTOR_REACHABLE_COLOR

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

Definition at line 94 of file robot_interaction.cpp.

◆ END_EFFECTOR_UNREACHABLE_COLOR

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

Definition at line 93 of file robot_interaction.cpp.

◆ SQRT2INV

const double robot_interaction::SQRT2INV = 0.707106781
static

Definition at line 174 of file interactive_marker_helpers.cpp.



robot_interaction
Author(s): Ioan Sucan
autogenerated on Sat Mar 15 2025 02:26:54