#include <robot_interaction.h>
Classes | |
struct | EndEffector |
Representation of an interaction via an end-effector. More... | |
struct | Generic |
Representation of a generic interaction. Displays one interactive marker. More... | |
class | InteractionHandler |
struct | Joint |
Representation of an interaction via a joint. More... | |
Public Types | |
enum | EndEffectorInteractionStyle { EEF_POSITION_ARROWS = 1, EEF_ORIENTATION_CIRCLES = 2, EEF_POSITION_SPHERE = 4, EEF_ORIENTATION_SPHERE = 8, EEF_POSITION_EEF = 16, EEF_ORIENTATION_EEF = 32, EEF_FIXED = 64, EEF_POSITION, EEF_ORIENTATION, EEF_6DOF, EEF_6DOF_SPHERE, EEF_POSITION_NOSPHERE, EEF_ORIENTATION_NOSPHERE, EEF_6DOF_NOSPHERE } |
The different types of interaction that can be constructed for an end effector. More... | |
typedef boost::function< void(InteractionHandler *, bool) | InteractionHandlerCallbackFn ) |
typedef boost::shared_ptr < const InteractionHandler > | InteractionHandlerConstPtr |
typedef boost::shared_ptr < InteractionHandler > | InteractionHandlerPtr |
typedef boost::function< bool(const robot_state::RobotState &, visualization_msgs::InteractiveMarker &)> | InteractiveMarkerConstructorFn |
typedef boost::function< bool(const robot_state::RobotState &, geometry_msgs::Pose &)> | InteractiveMarkerUpdateFn |
typedef boost::function< bool(robot_state::RobotState &, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &)> | ProcessFeedbackFn |
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, EndEffectorInteractionStyle style=EEF_6DOF) |
void | decideActiveEndEffectors (const std::string &group, EndEffectorInteractionStyle style=EEF_6DOF) |
called by decideActiveComponents(); add markers for end effectors | |
void | decideActiveJoints (const std::string &group) |
called by decideActiveComponents(); add markers for planar and floating joints | |
const std::vector< EndEffector > & | getActiveEndEffectors () const |
const std::vector< Joint > & | getActiveJoints () const |
const std::string & | getServerTopic (void) const |
void | publishInteractiveMarkers () |
RobotInteraction (const robot_model::RobotModelConstPtr &kmodel, const std::string &ns="") | |
bool | showingMarkers (const InteractionHandlerPtr &handler) |
void | updateInteractiveMarkers (const InteractionHandlerPtr &handler) |
virtual | ~RobotInteraction () |
Static Public Member Functions | |
static bool | updateState (robot_state::RobotState &state, const EndEffector &eef, const geometry_msgs::Pose &pose, unsigned int attempts, double ik_timeout, const robot_state::StateValidityCallbackFn &validity_callback=robot_state::StateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &kinematics_query_options=kinematics::KinematicsQueryOptions()) |
static bool | updateState (robot_state::RobotState &state, const Joint &vj, const geometry_msgs::Pose &pose) |
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 InteractionHandlerPtr &handler, const EndEffector &eef, visualization_msgs::InteractiveMarker &im, bool position=true, bool orientation=true) |
void | addEndEffectorMarkers (const InteractionHandlerPtr &handler, const EndEffector &eef, const geometry_msgs::Pose &offset, visualization_msgs::InteractiveMarker &im, bool position=true, bool orientation=true) |
void | clearInteractiveMarkersUnsafe () |
double | computeGroupMarkerSize (const std::string &group) |
void | computeMarkerPose (const InteractionHandlerPtr &handler, const EndEffector &eef, const robot_state::RobotState &robot_state, geometry_msgs::Pose &pose, geometry_msgs::Pose &control_to_eef_tf) const |
void | processingThread () |
void | processInteractiveMarkerFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
Private Attributes | |
std::vector< EndEffector > | active_eef_ |
std::vector< Generic > | active_generic_ |
std::vector< Joint > | active_vj_ |
std::map< std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr > | feedback_map_ |
std::map< std::string, InteractionHandlerPtr > | handlers_ |
interactive_markers::InteractiveMarkerServer * | int_marker_server_ |
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 61 of file robot_interaction.h.
typedef boost::function<void(InteractionHandler*, bool) robot_interaction::RobotInteraction::InteractionHandlerCallbackFn) |
This 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 wheher 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 162 of file robot_interaction.h.
typedef boost::shared_ptr<const InteractionHandler> robot_interaction::RobotInteraction::InteractionHandlerConstPtr |
Definition at line 429 of file robot_interaction.h.
typedef boost::shared_ptr<InteractionHandler> robot_interaction::RobotInteraction::InteractionHandlerPtr |
Definition at line 428 of file robot_interaction.h.
typedef boost::function<bool(const robot_state::RobotState&, visualization_msgs::InteractiveMarker&)> robot_interaction::RobotInteraction::InteractiveMarkerConstructorFn |
When using generic markers, a means to construct the marker is needed: this callback. The callback should set up the passed in marker according to the passed in robot state. Return true on success. Return false on failure or if the marker should not be added and displayed.
Definition at line 141 of file robot_interaction.h.
typedef boost::function<bool(const robot_state::RobotState&, geometry_msgs::Pose&)> robot_interaction::RobotInteraction::InteractiveMarkerUpdateFn |
When using generic markers, this callback is called when the robot state changes. Callback should calculate a new pose for the marker based on the passed in robot state. Return true if the pose was modified, false if no update is to be issued (pose is unchanged).
Definition at line 151 of file robot_interaction.h.
typedef boost::function<bool(robot_state::RobotState&, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &)> robot_interaction::RobotInteraction::ProcessFeedbackFn |
When using generic markers, this callback is called when the interactive marker changes and sends feedback. Callback should update the robot state that was passed in according to the new position of the marker. Return true if the update was successful. Return false if the state was not successfully updated.
Definition at line 146 of file robot_interaction.h.
The different types of interaction that can be constructed for an end effector.
Definition at line 70 of file robot_interaction.h.
robot_interaction::RobotInteraction::RobotInteraction | ( | const robot_model::RobotModelConstPtr & | kmodel, |
const std::string & | ns = "" |
||
) |
Definition at line 420 of file robot_interaction.cpp.
robot_interaction::RobotInteraction::~RobotInteraction | ( | ) | [virtual] |
Definition at line 431 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::addActiveComponent | ( | const InteractiveMarkerConstructorFn & | construct, |
const ProcessFeedbackFn & | process, | ||
const InteractiveMarkerUpdateFn & | update = InteractiveMarkerUpdateFn() , |
||
const std::string & | name = "" |
||
) |
Definition at line 449 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::addEndEffectorMarkers | ( | const InteractionHandlerPtr & | handler, |
const EndEffector & | eef, | ||
visualization_msgs::InteractiveMarker & | im, | ||
bool | position = true , |
||
bool | orientation = true |
||
) | [private] |
Definition at line 681 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::addEndEffectorMarkers | ( | const InteractionHandlerPtr & | handler, |
const EndEffector & | eef, | ||
const geometry_msgs::Pose & | offset, | ||
visualization_msgs::InteractiveMarker & | im, | ||
bool | position = true , |
||
bool | orientation = true |
||
) | [private] |
Definition at line 691 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::addInteractiveMarkers | ( | const InteractionHandlerPtr & | handler, |
const double | marker_scale = 0.0 |
||
) |
Definition at line 759 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::clear | ( | void | ) |
Definition at line 658 of file robot_interaction.cpp.
Definition at line 668 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::clearInteractiveMarkersUnsafe | ( | ) | [private] |
Definition at line 674 of file robot_interaction.cpp.
double robot_interaction::RobotInteraction::computeGroupMarkerSize | ( | const std::string & | group | ) | [private] |
Definition at line 464 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::computeMarkerPose | ( | const InteractionHandlerPtr & | handler, |
const EndEffector & | eef, | ||
const robot_state::RobotState & | robot_state, | ||
geometry_msgs::Pose & | pose, | ||
geometry_msgs::Pose & | control_to_eef_tf | ||
) | const [private] |
Definition at line 865 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::decideActiveComponents | ( | const std::string & | group, |
EndEffectorInteractionStyle | style = EEF_6DOF |
||
) |
Definition at line 441 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::decideActiveEndEffectors | ( | const std::string & | group, |
EndEffectorInteractionStyle | style = EEF_6DOF |
||
) |
called by decideActiveComponents(); add markers for end effectors
Definition at line 577 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::decideActiveJoints | ( | const std::string & | group | ) |
called by decideActiveComponents(); add markers for planar and floating joints
Definition at line 509 of file robot_interaction.cpp.
const std::vector<EndEffector>& robot_interaction::RobotInteraction::getActiveEndEffectors | ( | ) | const [inline] |
Definition at line 471 of file robot_interaction.h.
const std::vector<Joint>& robot_interaction::RobotInteraction::getActiveJoints | ( | ) | const [inline] |
Definition at line 476 of file robot_interaction.h.
const std::string& robot_interaction::RobotInteraction::getServerTopic | ( | void | ) | const [inline] |
Definition at line 434 of file robot_interaction.h.
void robot_interaction::RobotInteraction::processingThread | ( | ) | [private] |
Definition at line 1010 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::processInteractiveMarkerFeedback | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [private] |
Definition at line 988 of file robot_interaction.cpp.
Definition at line 929 of file robot_interaction.cpp.
bool robot_interaction::RobotInteraction::showingMarkers | ( | const InteractionHandlerPtr & | handler | ) |
Definition at line 935 of file robot_interaction.cpp.
void robot_interaction::RobotInteraction::updateInteractiveMarkers | ( | const InteractionHandlerPtr & | handler | ) |
Definition at line 895 of file robot_interaction.cpp.
bool robot_interaction::RobotInteraction::updateState | ( | robot_state::RobotState & | state, |
const EndEffector & | eef, | ||
const geometry_msgs::Pose & | pose, | ||
unsigned int | attempts, | ||
double | ik_timeout, | ||
const robot_state::StateValidityCallbackFn & | validity_callback = robot_state::StateValidityCallbackFn() , |
||
const kinematics::KinematicsQueryOptions & | kinematics_query_options = kinematics::KinematicsQueryOptions() |
||
) | [static] |
Definition at line 979 of file robot_interaction.cpp.
bool robot_interaction::RobotInteraction::updateState | ( | robot_state::RobotState & | state, |
const Joint & | vj, | ||
const geometry_msgs::Pose & | pose | ||
) | [static] |
Definition at line 951 of file robot_interaction.cpp.
std::vector<EndEffector> robot_interaction::RobotInteraction::active_eef_ [private] |
Definition at line 508 of file robot_interaction.h.
std::vector<Generic> robot_interaction::RobotInteraction::active_generic_ [private] |
Definition at line 510 of file robot_interaction.h.
std::vector<Joint> robot_interaction::RobotInteraction::active_vj_ [private] |
Definition at line 509 of file robot_interaction.h.
std::map<std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr> robot_interaction::RobotInteraction::feedback_map_ [private] |
Definition at line 504 of file robot_interaction.h.
std::map<std::string, InteractionHandlerPtr> robot_interaction::RobotInteraction::handlers_ [private] |
Definition at line 512 of file robot_interaction.h.
interactive_markers::InteractiveMarkerServer* robot_interaction::RobotInteraction::int_marker_server_ [private] |
Definition at line 525 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 66 of file robot_interaction.h.
boost::mutex robot_interaction::RobotInteraction::marker_access_lock_ [private] |
Definition at line 523 of file robot_interaction.h.
boost::condition_variable robot_interaction::RobotInteraction::new_feedback_condition_ [private] |
Definition at line 503 of file robot_interaction.h.
boost::scoped_ptr<boost::thread> robot_interaction::RobotInteraction::processing_thread_ [private] |
Definition at line 500 of file robot_interaction.h.
Definition at line 506 of file robot_interaction.h.
bool robot_interaction::RobotInteraction::run_processing_thread_ [private] |
Definition at line 501 of file robot_interaction.h.
std::map<std::string, std::size_t> robot_interaction::RobotInteraction::shown_markers_ [private] |
Definition at line 513 of file robot_interaction.h.
std::string robot_interaction::RobotInteraction::topic_ [private] |
Definition at line 526 of file robot_interaction.h.