Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
robot_interaction::RobotInteraction Class Reference

#include <robot_interaction.h>

Public Member Functions

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

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. More...
 

Private Member Functions

void addEndEffectorMarkers (const InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, const geometry_msgs::Pose &offset, visualization_msgs::InteractiveMarker &im, bool position=true, bool orientation=true)
 
void addEndEffectorMarkers (const InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, visualization_msgs::InteractiveMarker &im, bool position=true, bool orientation=true)
 
void clearInteractiveMarkersUnsafe ()
 
double computeGroupMarkerSize (const std::string &group)
 
double computeLinkMarkerSize (const std::string &link)
 
void computeMarkerPose (const InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, const moveit::core::RobotState &robot_state, geometry_msgs::Pose &pose, geometry_msgs::Pose &control_to_eef_tf) const
 
void decideActiveEndEffectors (const std::string &group)
 
void decideActiveEndEffectors (const std::string &group, InteractionStyle::InteractionStyle style)
 
void decideActiveJoints (const std::string &group)
 
void moveInteractiveMarker (const std::string &name, const geometry_msgs::PoseStamped &msg)
 
void processingThread ()
 
void processInteractiveMarkerFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
void registerMoveInteractiveMarkerTopic (const std::string &marker_name, const std::string &name)
 
void subscribeMoveInteractiveMarker (const std::string marker_name, const std::string &name)
 

Private Attributes

std::vector< EndEffectorInteractionactive_eef_
 
std::vector< GenericInteractionactive_generic_
 
std::vector< JointInteractionactive_vj_
 
std::map< std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr > feedback_map_
 
std::map< std::string, InteractionHandlerPtr > handlers_
 
std::vector< ros::Subscriberint_marker_move_subscribers_
 
std::vector< std::string > int_marker_move_topics_
 
std::vector< std::string > int_marker_names_
 
interactive_markers::InteractiveMarkerServerint_marker_server_
 
KinematicOptionsMapPtr kinematic_options_map_
 
boost::mutex marker_access_lock_
 
boost::condition_variable new_feedback_condition_
 
std::unique_ptr< boost::thread > processing_thread_
 
moveit::core::RobotModelConstPtr robot_model_
 
bool run_processing_thread_
 
std::map< std::string, std::size_t > shown_markers_
 
std::string topic_
 

Detailed Description

Definition at line 72 of file robot_interaction.h.

Constructor & Destructor Documentation

◆ RobotInteraction()

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

Definition at line 98 of file robot_interaction.cpp.

◆ ~RobotInteraction()

robot_interaction::RobotInteraction::~RobotInteraction ( )
virtual

Definition at line 109 of file robot_interaction.cpp.

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

◆ addEndEffectorMarkers() [1/2]

void robot_interaction::RobotInteraction::addEndEffectorMarkers ( const InteractionHandlerPtr &  handler,
const EndEffectorInteraction eef,
const geometry_msgs::Pose &  offset,
visualization_msgs::InteractiveMarker &  im,
bool  position = true,
bool  orientation = true 
)
private

Definition at line 414 of file robot_interaction.cpp.

◆ addEndEffectorMarkers() [2/2]

void robot_interaction::RobotInteraction::addEndEffectorMarkers ( const InteractionHandlerPtr &  handler,
const EndEffectorInteraction eef,
visualization_msgs::InteractiveMarker &  im,
bool  position = true,
bool  orientation = true 
)
private

Definition at line 406 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 482 of file robot_interaction.cpp.

◆ clear()

void robot_interaction::RobotInteraction::clear ( )

remove all interactions. Also removes all markers.

Definition at line 380 of file robot_interaction.cpp.

◆ clearInteractiveMarkers()

void robot_interaction::RobotInteraction::clearInteractiveMarkers ( )

Definition at line 390 of file robot_interaction.cpp.

◆ clearInteractiveMarkersUnsafe()

void robot_interaction::RobotInteraction::clearInteractiveMarkersUnsafe ( )
private

Definition at line 396 of file robot_interaction.cpp.

◆ computeGroupMarkerSize()

double robot_interaction::RobotInteraction::computeGroupMarkerSize ( const std::string &  group)
private

Definition at line 180 of file robot_interaction.cpp.

◆ computeLinkMarkerSize()

double robot_interaction::RobotInteraction::computeLinkMarkerSize ( const std::string &  link)
private

Definition at line 150 of file robot_interaction.cpp.

◆ computeMarkerPose()

void robot_interaction::RobotInteraction::computeMarkerPose ( const InteractionHandlerPtr &  handler,
const EndEffectorInteraction eef,
const moveit::core::RobotState robot_state,
geometry_msgs::Pose &  pose,
geometry_msgs::Pose &  control_to_eef_tf 
) const
private

Definition at line 620 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 119 of file robot_interaction.cpp.

◆ decideActiveComponents() [2/2]

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

Definition at line 124 of file robot_interaction.cpp.

◆ decideActiveEndEffectors() [1/2]

void robot_interaction::RobotInteraction::decideActiveEndEffectors ( const std::string &  group)
private

Definition at line 288 of file robot_interaction.cpp.

◆ decideActiveEndEffectors() [2/2]

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

Definition at line 293 of file robot_interaction.cpp.

◆ decideActiveJoints()

void robot_interaction::RobotInteraction::decideActiveJoints ( const std::string &  group)
private

Definition at line 217 of file robot_interaction.cpp.

◆ getActiveEndEffectors()

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

Definition at line 157 of file robot_interaction.h.

◆ getActiveJoints()

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

Definition at line 161 of file robot_interaction.h.

◆ getKinematicOptionsMap()

KinematicOptionsMapPtr robot_interaction::RobotInteraction::getKinematicOptionsMap ( )
inline

Definition at line 149 of file robot_interaction.h.

◆ getRobotModel()

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

Definition at line 142 of file robot_interaction.h.

◆ getServerTopic()

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

Definition at line 81 of file robot_interaction.h.

◆ moveInteractiveMarker()

void robot_interaction::RobotInteraction::moveInteractiveMarker ( const std::string &  name,
const geometry_msgs::PoseStamped &  msg 
)
private

Definition at line 711 of file robot_interaction.cpp.

◆ processingThread()

void robot_interaction::RobotInteraction::processingThread ( )
private

Definition at line 753 of file robot_interaction.cpp.

◆ processInteractiveMarkerFeedback()

void robot_interaction::RobotInteraction::processInteractiveMarkerFeedback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)
private

Definition at line 730 of file robot_interaction.cpp.

◆ publishInteractiveMarkers()

void robot_interaction::RobotInteraction::publishInteractiveMarkers ( )

Definition at line 689 of file robot_interaction.cpp.

◆ registerMoveInteractiveMarkerTopic()

void robot_interaction::RobotInteraction::registerMoveInteractiveMarkerTopic ( const std::string &  marker_name,
const std::string &  name 
)
private

Definition at line 585 of file robot_interaction.cpp.

◆ showingMarkers()

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

Definition at line 695 of file robot_interaction.cpp.

◆ subscribeMoveInteractiveMarker()

void robot_interaction::RobotInteraction::subscribeMoveInteractiveMarker ( const std::string  marker_name,
const std::string &  name 
)
private

◆ toggleMoveInteractiveMarkerTopic()

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

Definition at line 594 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

◆ active_eef_

std::vector<EndEffectorInteraction> robot_interaction::RobotInteraction::active_eef_
private

Definition at line 203 of file robot_interaction.h.

◆ active_generic_

std::vector<GenericInteraction> robot_interaction::RobotInteraction::active_generic_
private

Definition at line 205 of file robot_interaction.h.

◆ active_vj_

std::vector<JointInteraction> robot_interaction::RobotInteraction::active_vj_
private

Definition at line 204 of file robot_interaction.h.

◆ feedback_map_

std::map<std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr> robot_interaction::RobotInteraction::feedback_map_
private

Definition at line 199 of file robot_interaction.h.

◆ handlers_

std::map<std::string, InteractionHandlerPtr> robot_interaction::RobotInteraction::handlers_
private

Definition at line 207 of file robot_interaction.h.

◆ int_marker_move_subscribers_

std::vector<ros::Subscriber> robot_interaction::RobotInteraction::int_marker_move_subscribers_
private

Definition at line 222 of file robot_interaction.h.

◆ int_marker_move_topics_

std::vector<std::string> robot_interaction::RobotInteraction::int_marker_move_topics_
private

Definition at line 225 of file robot_interaction.h.

◆ int_marker_names_

std::vector<std::string> robot_interaction::RobotInteraction::int_marker_names_
private

Definition at line 227 of file robot_interaction.h.

◆ int_marker_server_

interactive_markers::InteractiveMarkerServer* robot_interaction::RobotInteraction::int_marker_server_
private

Definition at line 220 of file robot_interaction.h.

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

◆ kinematic_options_map_

KinematicOptionsMapPtr robot_interaction::RobotInteraction::kinematic_options_map_
private

Definition at line 232 of file robot_interaction.h.

◆ marker_access_lock_

boost::mutex robot_interaction::RobotInteraction::marker_access_lock_
private

Definition at line 218 of file robot_interaction.h.

◆ new_feedback_condition_

boost::condition_variable robot_interaction::RobotInteraction::new_feedback_condition_
private

Definition at line 198 of file robot_interaction.h.

◆ processing_thread_

std::unique_ptr<boost::thread> robot_interaction::RobotInteraction::processing_thread_
private

Definition at line 195 of file robot_interaction.h.

◆ robot_model_

moveit::core::RobotModelConstPtr robot_interaction::RobotInteraction::robot_model_
private

Definition at line 201 of file robot_interaction.h.

◆ run_processing_thread_

bool robot_interaction::RobotInteraction::run_processing_thread_
private

Definition at line 196 of file robot_interaction.h.

◆ shown_markers_

std::map<std::string, std::size_t> robot_interaction::RobotInteraction::shown_markers_
private

Definition at line 208 of file robot_interaction.h.

◆ topic_

std::string robot_interaction::RobotInteraction::topic_
private

Definition at line 229 of file robot_interaction.h.


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


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