#include <robot_interaction.h>
|
static const std::string | INTERACTIVE_MARKER_TOPIC = "robot_interaction_interactive_marker_topic" |
| The topic name on which the internal Interactive Marker Server operates. More...
|
|
|
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) |
|
Definition at line 72 of file robot_interaction.h.
◆ RobotInteraction()
robot_interaction::RobotInteraction::RobotInteraction |
( |
const moveit::core::RobotModelConstPtr & |
robot_model, |
|
|
const std::string & |
ns = "" |
|
) |
| |
◆ ~RobotInteraction()
robot_interaction::RobotInteraction::~RobotInteraction |
( |
| ) |
|
|
virtual |
◆ addActiveComponent()
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 |
◆ 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 |
◆ 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 |
( |
| ) |
|
◆ clearInteractiveMarkers()
void robot_interaction::RobotInteraction::clearInteractiveMarkers |
( |
| ) |
|
◆ clearInteractiveMarkersUnsafe()
void robot_interaction::RobotInteraction::clearInteractiveMarkersUnsafe |
( |
| ) |
|
|
private |
◆ computeGroupMarkerSize()
double robot_interaction::RobotInteraction::computeGroupMarkerSize |
( |
const std::string & |
group | ) |
|
|
private |
◆ computeLinkMarkerSize()
double robot_interaction::RobotInteraction::computeLinkMarkerSize |
( |
const std::string & |
link | ) |
|
|
private |
◆ 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 |
◆ 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]
◆ decideActiveEndEffectors() [1/2]
void robot_interaction::RobotInteraction::decideActiveEndEffectors |
( |
const std::string & |
group | ) |
|
|
private |
◆ decideActiveEndEffectors() [2/2]
◆ decideActiveJoints()
void robot_interaction::RobotInteraction::decideActiveJoints |
( |
const std::string & |
group | ) |
|
|
private |
◆ getActiveEndEffectors()
const std::vector<EndEffectorInteraction>& robot_interaction::RobotInteraction::getActiveEndEffectors |
( |
| ) |
const |
|
inline |
◆ getActiveJoints()
const std::vector<JointInteraction>& robot_interaction::RobotInteraction::getActiveJoints |
( |
| ) |
const |
|
inline |
◆ getKinematicOptionsMap()
KinematicOptionsMapPtr robot_interaction::RobotInteraction::getKinematicOptionsMap |
( |
| ) |
|
|
inline |
◆ getRobotModel()
const moveit::core::RobotModelConstPtr& robot_interaction::RobotInteraction::getRobotModel |
( |
| ) |
const |
|
inline |
◆ getServerTopic()
const std::string& robot_interaction::RobotInteraction::getServerTopic |
( |
| ) |
const |
|
inline |
◆ moveInteractiveMarker()
void robot_interaction::RobotInteraction::moveInteractiveMarker |
( |
const std::string & |
name, |
|
|
const geometry_msgs::PoseStamped & |
msg |
|
) |
| |
|
private |
◆ processingThread()
void robot_interaction::RobotInteraction::processingThread |
( |
| ) |
|
|
private |
◆ processInteractiveMarkerFeedback()
void robot_interaction::RobotInteraction::processInteractiveMarkerFeedback |
( |
const visualization_msgs::InteractiveMarkerFeedbackConstPtr & |
feedback | ) |
|
|
private |
◆ publishInteractiveMarkers()
void robot_interaction::RobotInteraction::publishInteractiveMarkers |
( |
| ) |
|
◆ registerMoveInteractiveMarkerTopic()
void robot_interaction::RobotInteraction::registerMoveInteractiveMarkerTopic |
( |
const std::string & |
marker_name, |
|
|
const std::string & |
name |
|
) |
| |
|
private |
◆ showingMarkers()
bool robot_interaction::RobotInteraction::showingMarkers |
( |
const InteractionHandlerPtr & |
handler | ) |
|
◆ subscribeMoveInteractiveMarker()
void robot_interaction::RobotInteraction::subscribeMoveInteractiveMarker |
( |
const std::string |
marker_name, |
|
|
const std::string & |
name |
|
) |
| |
|
private |
◆ toggleMoveInteractiveMarkerTopic()
void robot_interaction::RobotInteraction::toggleMoveInteractiveMarkerTopic |
( |
bool |
enable | ) |
|
◆ updateInteractiveMarkers()
void robot_interaction::RobotInteraction::updateInteractiveMarkers |
( |
const InteractionHandlerPtr & |
handler | ) |
|
◆ active_eef_
◆ active_generic_
◆ active_vj_
◆ feedback_map_
std::map<std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr> robot_interaction::RobotInteraction::feedback_map_ |
|
private |
◆ handlers_
std::map<std::string, InteractionHandlerPtr> robot_interaction::RobotInteraction::handlers_ |
|
private |
◆ int_marker_move_subscribers_
std::vector<ros::Subscriber> robot_interaction::RobotInteraction::int_marker_move_subscribers_ |
|
private |
◆ int_marker_move_topics_
std::vector<std::string> robot_interaction::RobotInteraction::int_marker_move_topics_ |
|
private |
◆ int_marker_names_
std::vector<std::string> robot_interaction::RobotInteraction::int_marker_names_ |
|
private |
◆ int_marker_server_
◆ 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 |
◆ marker_access_lock_
boost::mutex robot_interaction::RobotInteraction::marker_access_lock_ |
|
private |
◆ new_feedback_condition_
boost::condition_variable robot_interaction::RobotInteraction::new_feedback_condition_ |
|
private |
◆ processing_thread_
std::unique_ptr<boost::thread> robot_interaction::RobotInteraction::processing_thread_ |
|
private |
◆ robot_model_
moveit::core::RobotModelConstPtr robot_interaction::RobotInteraction::robot_model_ |
|
private |
◆ run_processing_thread_
bool robot_interaction::RobotInteraction::run_processing_thread_ |
|
private |
◆ shown_markers_
std::map<std::string, std::size_t> robot_interaction::RobotInteraction::shown_markers_ |
|
private |
◆ topic_
std::string robot_interaction::RobotInteraction::topic_ |
|
private |
The documentation for this class was generated from the following files: