#include <robot_interaction.h>
Public Types | |
typedef ::robot_interaction::EndEffectorInteraction | EndEffector |
enum | EndEffectorInteractionStyle { EEF_POSITION_ARROWS = InteractionStyle::POSITION_ARROWS, EEF_ORIENTATION_CIRCLES = InteractionStyle::ORIENTATION_CIRCLES, EEF_POSITION_SPHERE = InteractionStyle::POSITION_SPHERE, EEF_ORIENTATION_SPHERE = InteractionStyle::ORIENTATION_SPHERE, EEF_POSITION_EEF = InteractionStyle::POSITION_EEF, EEF_ORIENTATION_EEF = InteractionStyle::ORIENTATION_EEF, EEF_FIXED = InteractionStyle::FIXED, EEF_POSITION = InteractionStyle::POSITION, EEF_ORIENTATION = InteractionStyle::ORIENTATION, EEF_6DOF = InteractionStyle::SIX_DOF, EEF_6DOF_SPHERE = InteractionStyle::SIX_DOF_SPHERE, EEF_POSITION_NOSPHERE = InteractionStyle::POSITION_NOSPHERE, EEF_ORIENTATION_NOSPHERE = InteractionStyle::ORIENTATION_NOSPHERE, EEF_6DOF_NOSPHERE = InteractionStyle::SIX_DOF_NOSPHERE } |
typedef ::robot_interaction::GenericInteraction | Generic |
typedef ::robot_interaction::InteractionHandler | InteractionHandler |
typedef ::robot_interaction::InteractionHandlerPtr | InteractionHandlerPtr |
typedef ::robot_interaction::JointInteraction | Joint |
Public Member Functions | |
void | addActiveComponent (const InteractiveMarkerConstructorFn &construct, const ProcessFeedbackFn &process, const InteractiveMarkerUpdateFn &update=InteractiveMarkerUpdateFn(), const std::string &name="") |
void | addInteractiveMarkers (const ::robot_interaction::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) |
void | decideActiveComponents (const std::string &group, EndEffectorInteractionStyle style) |
void | decideActiveEndEffectors (const std::string &group, EndEffectorInteractionStyle style) |
const std::vector < EndEffectorInteraction > & | getActiveEndEffectors () const |
const std::vector < JointInteraction > & | getActiveJoints () const |
KinematicOptionsMapPtr | getKinematicOptionsMap () |
const robot_model::RobotModelConstPtr & | getRobotModel () const |
const std::string & | getServerTopic (void) const |
void | publishInteractiveMarkers () |
RobotInteraction (const robot_model::RobotModelConstPtr &kmodel, const std::string &ns="") | |
bool | showingMarkers (const ::robot_interaction::InteractionHandlerPtr &handler) |
void | toggleMoveInteractiveMarkerTopic (bool enable) |
void | updateInteractiveMarkers (const ::robot_interaction::InteractionHandlerPtr &handler) |
virtual | ~RobotInteraction () |
Static Public Member Functions | |
static bool | updateState (robot_state::RobotState &state, const EndEffectorInteraction &eef, const geometry_msgs::Pose &pose, unsigned int attempts, double ik_timeout, const robot_state::GroupStateValidityCallbackFn &validity_callback=robot_state::GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &kinematics_query_options=kinematics::KinematicsQueryOptions()) |
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. | |
Private Member Functions | |
void | addEndEffectorMarkers (const ::robot_interaction::InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, visualization_msgs::InteractiveMarker &im, bool position=true, bool orientation=true) |
void | addEndEffectorMarkers (const ::robot_interaction::InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, const geometry_msgs::Pose &offset, 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 ::robot_interaction::InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, const robot_state::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::PoseStampedConstPtr &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 < EndEffectorInteraction > | active_eef_ |
std::vector< GenericInteraction > | active_generic_ |
std::vector< JointInteraction > | active_vj_ |
std::map< std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr > | feedback_map_ |
std::map< std::string,::robot_interaction::InteractionHandlerPtr > | handlers_ |
std::vector< ros::Subscriber > | int_marker_move_subscribers_ |
std::vector< std::string > | int_marker_move_topics_ |
std::vector< std::string > | int_marker_names_ |
interactive_markers::InteractiveMarkerServer * | int_marker_server_ |
KinematicOptionsMapPtr | kinematic_options_map_ |
boost::mutex | marker_access_lock_ |
boost::condition_variable | new_feedback_condition_ |
boost::scoped_ptr< boost::thread > | processing_thread_ |
robot_model::RobotModelConstPtr | robot_model_ |
bool | run_processing_thread_ |
std::map< std::string, std::size_t > | shown_markers_ |
std::string | topic_ |
Definition at line 73 of file robot_interaction.h.
typedef ::robot_interaction::EndEffectorInteraction robot_interaction::RobotInteraction::EndEffector |
Definition at line 79 of file robot_interaction.h.
Definition at line 81 of file robot_interaction.h.
typedef ::robot_interaction::InteractionHandler robot_interaction::RobotInteraction::InteractionHandler |
Definition at line 77 of file robot_interaction.h.
typedef ::robot_interaction::InteractionHandlerPtr robot_interaction::RobotInteraction::InteractionHandlerPtr |
Definition at line 78 of file robot_interaction.h.
Definition at line 80 of file robot_interaction.h.
DEPRECATED. Instead use robot_interaction::InteractionStyle::InteractionStyle in interaction.h
Definition at line 247 of file robot_interaction.h.
robot_interaction::RobotInteraction::RobotInteraction | ( | const robot_model::RobotModelConstPtr & | kmodel, |
const std::string & | ns = "" |
||
) |
Definition at line 64 of file robot_interaction.cpp.
robot_interaction::RobotInteraction::~RobotInteraction | ( | ) | [virtual] |
Definition at line 75 of file robot_interaction.cpp.
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 101 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::addEndEffectorMarkers | ( | const ::robot_interaction::InteractionHandlerPtr & | handler, |
const EndEffectorInteraction & | eef, | ||
visualization_msgs::InteractiveMarker & | im, | ||
bool | position = true , |
||
bool | orientation = true |
||
) | [private] |
Definition at line 375 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::addEndEffectorMarkers | ( | const ::robot_interaction::InteractionHandlerPtr & | handler, |
const EndEffectorInteraction & | eef, | ||
const geometry_msgs::Pose & | offset, | ||
visualization_msgs::InteractiveMarker & | im, | ||
bool | position = true , |
||
bool | orientation = true |
||
) | [private] |
Definition at line 384 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::addInteractiveMarkers | ( | const ::robot_interaction::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 454 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::clear | ( | void | ) |
remove all interactions. Also removes all markers.
Definition at line 349 of file robot_interaction.cpp.
Definition at line 359 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::clearInteractiveMarkersUnsafe | ( | ) | [private] |
Definition at line 365 of file robot_interaction.cpp.
double robot_interaction::RobotInteraction::computeGroupMarkerSize | ( | const std::string & | group | ) | [private] |
Definition at line 146 of file robot_interaction.cpp.
double robot_interaction::RobotInteraction::computeLinkMarkerSize | ( | const std::string & | link | ) | [private] |
Definition at line 116 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::computeMarkerPose | ( | const ::robot_interaction::InteractionHandlerPtr & | handler, |
const EndEffectorInteraction & | eef, | ||
const robot_state::RobotState & | robot_state, | ||
geometry_msgs::Pose & | pose, | ||
geometry_msgs::Pose & | control_to_eef_tf | ||
) | const [private] |
Definition at line 598 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::decideActiveComponents | ( | const std::string & | group | ) |
Adds an interaction for:
Definition at line 85 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::decideActiveComponents | ( | const std::string & | group, |
InteractionStyle::InteractionStyle | style | ||
) |
Definition at line 90 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::decideActiveComponents | ( | const std::string & | group, |
EndEffectorInteractionStyle | style | ||
) |
Definition at line 867 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::decideActiveEndEffectors | ( | const std::string & | group | ) | [private] |
Definition at line 254 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::decideActiveEndEffectors | ( | const std::string & | group, |
InteractionStyle::InteractionStyle | style | ||
) | [private] |
Definition at line 259 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::decideActiveEndEffectors | ( | const std::string & | group, |
EndEffectorInteractionStyle | style | ||
) |
Definition at line 873 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::decideActiveJoints | ( | const std::string & | group | ) | [private] |
Definition at line 183 of file robot_interaction.cpp.
const std::vector<EndEffectorInteraction>& robot_interaction::RobotInteraction::getActiveEndEffectors | ( | ) | const [inline] |
Definition at line 269 of file robot_interaction.h.
const std::vector<JointInteraction>& robot_interaction::RobotInteraction::getActiveJoints | ( | ) | const [inline] |
Definition at line 274 of file robot_interaction.h.
KinematicOptionsMapPtr robot_interaction::RobotInteraction::getKinematicOptionsMap | ( | ) | [inline] |
Definition at line 159 of file robot_interaction.h.
const robot_model::RobotModelConstPtr& robot_interaction::RobotInteraction::getRobotModel | ( | ) | const [inline] |
Definition at line 152 of file robot_interaction.h.
const std::string& robot_interaction::RobotInteraction::getServerTopic | ( | void | ) | const [inline] |
Definition at line 90 of file robot_interaction.h.
void robot_interaction::RobotInteraction::moveInteractiveMarker | ( | const std::string | name, |
const geometry_msgs::PoseStampedConstPtr & | msg | ||
) | [private] |
Definition at line 706 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::processingThread | ( | ) | [private] |
Definition at line 748 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::processInteractiveMarkerFeedback | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [private] |
Definition at line 725 of file robot_interaction.cpp.
Definition at line 668 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::registerMoveInteractiveMarkerTopic | ( | const std::string | marker_name, |
const std::string & | name | ||
) | [private] |
Definition at line 564 of file robot_interaction.cpp.
bool robot_interaction::RobotInteraction::showingMarkers | ( | const ::robot_interaction::InteractionHandlerPtr & | handler | ) |
Definition at line 674 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::subscribeMoveInteractiveMarker | ( | const std::string | marker_name, |
const std::string & | name | ||
) | [private] |
void robot_interaction::RobotInteraction::toggleMoveInteractiveMarkerTopic | ( | bool | enable | ) |
Definition at line 574 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::updateInteractiveMarkers | ( | const ::robot_interaction::InteractionHandlerPtr & | handler | ) |
Definition at line 627 of file robot_interaction.cpp.
bool robot_interaction::RobotInteraction::updateState | ( | robot_state::RobotState & | state, |
const EndEffectorInteraction & | eef, | ||
const geometry_msgs::Pose & | pose, | ||
unsigned int | attempts, | ||
double | ik_timeout, | ||
const robot_state::GroupStateValidityCallbackFn & | validity_callback = robot_state::GroupStateValidityCallbackFn() , |
||
const kinematics::KinematicsQueryOptions & | kinematics_query_options = kinematics::KinematicsQueryOptions() |
||
) | [static] |
Definition at line 691 of file robot_interaction.cpp.
std::vector<EndEffectorInteraction> robot_interaction::RobotInteraction::active_eef_ [private] |
Definition at line 208 of file robot_interaction.h.
std::vector<GenericInteraction> robot_interaction::RobotInteraction::active_generic_ [private] |
Definition at line 210 of file robot_interaction.h.
std::vector<JointInteraction> robot_interaction::RobotInteraction::active_vj_ [private] |
Definition at line 209 of file robot_interaction.h.
std::map<std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr> robot_interaction::RobotInteraction::feedback_map_ [private] |
Definition at line 204 of file robot_interaction.h.
std::map<std::string, ::robot_interaction::InteractionHandlerPtr> robot_interaction::RobotInteraction::handlers_ [private] |
Definition at line 212 of file robot_interaction.h.
std::vector<ros::Subscriber> robot_interaction::RobotInteraction::int_marker_move_subscribers_ [private] |
Definition at line 227 of file robot_interaction.h.
std::vector<std::string> robot_interaction::RobotInteraction::int_marker_move_topics_ [private] |
Definition at line 230 of file robot_interaction.h.
std::vector<std::string> robot_interaction::RobotInteraction::int_marker_names_ [private] |
Definition at line 232 of file robot_interaction.h.
interactive_markers::InteractiveMarkerServer* robot_interaction::RobotInteraction::int_marker_server_ [private] |
Definition at line 225 of file robot_interaction.h.
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 85 of file robot_interaction.h.
KinematicOptionsMapPtr robot_interaction::RobotInteraction::kinematic_options_map_ [private] |
Definition at line 238 of file robot_interaction.h.
boost::mutex robot_interaction::RobotInteraction::marker_access_lock_ [private] |
Definition at line 223 of file robot_interaction.h.
boost::condition_variable robot_interaction::RobotInteraction::new_feedback_condition_ [private] |
Definition at line 203 of file robot_interaction.h.
boost::scoped_ptr<boost::thread> robot_interaction::RobotInteraction::processing_thread_ [private] |
Definition at line 200 of file robot_interaction.h.
robot_model::RobotModelConstPtr robot_interaction::RobotInteraction::robot_model_ [private] |
Definition at line 206 of file robot_interaction.h.
bool robot_interaction::RobotInteraction::run_processing_thread_ [private] |
Definition at line 201 of file robot_interaction.h.
std::map<std::string, std::size_t> robot_interaction::RobotInteraction::shown_markers_ [private] |
Definition at line 213 of file robot_interaction.h.
std::string robot_interaction::RobotInteraction::topic_ [private] |
Definition at line 234 of file robot_interaction.h.