moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | Static Public Attributes | List of all members
robot_interaction::RobotInteraction Class Reference

#include <robot_interaction.h>

Public Member Functions

 RobotInteraction (const moveit::core::RobotModelConstPtr &robot_model, const rclcpp::Node::SharedPtr &node, const std::string &ns="")
 
virtual ~RobotInteraction ()
 
const std::string & getServerTopic () const
 
void addActiveComponent (const InteractiveMarkerConstructorFn &construct, const ProcessFeedbackFn &process, const InteractiveMarkerUpdateFn &update=InteractiveMarkerUpdateFn(), const std::string &name="")
 
void decideActiveComponents (const std::string &group)
 
void decideActiveComponents (const std::string &group, InteractionStyle::InteractionStyle style)
 
void clear ()
 
void addInteractiveMarkers (const InteractionHandlerPtr &handler, const double marker_scale=0.0)
 
void updateInteractiveMarkers (const InteractionHandlerPtr &handler)
 
bool showingMarkers (const InteractionHandlerPtr &handler)
 
void publishInteractiveMarkers ()
 
void clearInteractiveMarkers ()
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 
KinematicOptionsMapPtr getKinematicOptionsMap ()
 
void toggleMoveInteractiveMarkerTopic (bool enable)
 
const std::vector< EndEffectorInteraction > & getActiveEndEffectors () const
 
const std::vector< JointInteraction > & getActiveJoints () const
 

Static Public Attributes

static const std::string INTERACTIVE_MARKER_TOPIC = "robot_interaction_interactive_marker_topic"
 The topic name on which the internal Interactive Marker Server operates.
 

Detailed Description

Definition at line 73 of file robot_interaction.h.

Constructor & Destructor Documentation

◆ RobotInteraction()

robot_interaction::RobotInteraction::RobotInteraction ( const moveit::core::RobotModelConstPtr &  robot_model,
const rclcpp::Node::SharedPtr &  node,
const std::string &  ns = "" 
)

Definition at line 64 of file robot_interaction.cpp.

◆ ~RobotInteraction()

robot_interaction::RobotInteraction::~RobotInteraction ( )
virtual

Definition at line 79 of file robot_interaction.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ addActiveComponent()

void robot_interaction::RobotInteraction::addActiveComponent ( const InteractiveMarkerConstructorFn construct,
const ProcessFeedbackFn process,
const InteractiveMarkerUpdateFn update = InteractiveMarkerUpdateFn(),
const std::string &  name = "" 
)

add an interaction. An interaction is a marker that can be used to manipulate the robot state. This function does not add any markers. To add markers for all active interactions call addInteractiveMarkers(). construct - a callback to construct the marker. See comment on InteractiveMarkerConstructorFn above. update - Called when the robot state changes. Updates the marker pose. Optional. See comment on InteractiveMarkerUpdateFn above. process - called when the marker moves. Updates the robot state. See comment on ProcessFeedbackFn above.

Definition at line 107 of file robot_interaction.cpp.

◆ addInteractiveMarkers()

void robot_interaction::RobotInteraction::addInteractiveMarkers ( const InteractionHandlerPtr &  handler,
const double  marker_scale = 0.0 
)

Add interactive markers for all active interactions. This adds markers just to the one handler. If there are multiple handlers call this for each handler for which you want markers. The markers are not actually added until you call publishInteractiveMarkers().

Definition at line 474 of file robot_interaction.cpp.

Here is the call graph for this function:

◆ clear()

void robot_interaction::RobotInteraction::clear ( )

remove all interactions. Also removes all markers.

Definition at line 365 of file robot_interaction.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ clearInteractiveMarkers()

void robot_interaction::RobotInteraction::clearInteractiveMarkers ( )

Definition at line 375 of file robot_interaction.cpp.

◆ decideActiveComponents() [1/2]

void robot_interaction::RobotInteraction::decideActiveComponents ( const std::string &  group)

Adds an interaction for:

  • each end effector in the group that can be controller by IK
  • each floating joint
  • each planar joint If no end effector exists in the robot then adds an interaction for the last link in the chain. This function does not add any markers. To add markers for all active interactions call addInteractiveMarkers().

Definition at line 89 of file robot_interaction.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ decideActiveComponents() [2/2]

void robot_interaction::RobotInteraction::decideActiveComponents ( const std::string &  group,
InteractionStyle::InteractionStyle  style 
)

Definition at line 94 of file robot_interaction.cpp.

◆ getActiveEndEffectors()

const std::vector< EndEffectorInteraction > & robot_interaction::RobotInteraction::getActiveEndEffectors ( ) const
inline

Definition at line 159 of file robot_interaction.h.

◆ getActiveJoints()

const std::vector< JointInteraction > & robot_interaction::RobotInteraction::getActiveJoints ( ) const
inline

Definition at line 163 of file robot_interaction.h.

◆ getKinematicOptionsMap()

KinematicOptionsMapPtr robot_interaction::RobotInteraction::getKinematicOptionsMap ( )
inline

Definition at line 151 of file robot_interaction.h.

◆ getRobotModel()

const moveit::core::RobotModelConstPtr & robot_interaction::RobotInteraction::getRobotModel ( ) const
inline

Definition at line 144 of file robot_interaction.h.

◆ getServerTopic()

const std::string & robot_interaction::RobotInteraction::getServerTopic ( ) const
inline

Definition at line 83 of file robot_interaction.h.

◆ publishInteractiveMarkers()

void robot_interaction::RobotInteraction::publishInteractiveMarkers ( )

Definition at line 689 of file robot_interaction.cpp.

Here is the caller graph for this function:

◆ showingMarkers()

bool robot_interaction::RobotInteraction::showingMarkers ( const InteractionHandlerPtr &  handler)

Definition at line 695 of file robot_interaction.cpp.

◆ toggleMoveInteractiveMarkerTopic()

void robot_interaction::RobotInteraction::toggleMoveInteractiveMarkerTopic ( bool  enable)

Definition at line 592 of file robot_interaction.cpp.

◆ updateInteractiveMarkers()

void robot_interaction::RobotInteraction::updateInteractiveMarkers ( const InteractionHandlerPtr &  handler)

Definition at line 649 of file robot_interaction.cpp.

Member Data Documentation

◆ INTERACTIVE_MARKER_TOPIC

const std::string robot_interaction::RobotInteraction::INTERACTIVE_MARKER_TOPIC = "robot_interaction_interactive_marker_topic"
static

The topic name on which the internal Interactive Marker Server operates.

Definition at line 77 of file robot_interaction.h.


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