#include <visualization_msgs/InteractiveMarkerFeedback.h>
#include <visualization_msgs/InteractiveMarker.h>
#include <interactive_markers/menu_handler.h>
#include <moveit/robot_state/robot_state.h>
#include <boost/function.hpp>
#include <boost/thread.hpp>
#include <tf/tf.h>
Go to the source code of this file.
Classes |
struct | robot_interaction::EndEffectorInteraction |
struct | robot_interaction::GenericInteraction |
struct | robot_interaction::JointInteraction |
Namespaces |
namespace | moveit |
namespace | moveit::core |
namespace | robot_interaction |
namespace | robot_interaction::InteractionStyle |
Typedefs |
typedef boost::function< bool(const
robot_state::RobotState &state,
visualization_msgs::InteractiveMarker
&marker)> | robot_interaction::InteractiveMarkerConstructorFn |
typedef boost::function< bool(const
robot_state::RobotState
&, geometry_msgs::Pose &)> | robot_interaction::InteractiveMarkerUpdateFn |
typedef boost::function< bool(robot_state::RobotState
&state, const
visualization_msgs::InteractiveMarkerFeedbackConstPtr
&feedback)> | robot_interaction::ProcessFeedbackFn |
Enumerations |
enum | robot_interaction::InteractionStyle::InteractionStyle {
robot_interaction::InteractionStyle::POSITION_ARROWS = 1,
robot_interaction::InteractionStyle::ORIENTATION_CIRCLES = 2,
robot_interaction::InteractionStyle::POSITION_SPHERE = 4,
robot_interaction::InteractionStyle::ORIENTATION_SPHERE = 8,
robot_interaction::InteractionStyle::POSITION_EEF = 16,
robot_interaction::InteractionStyle::ORIENTATION_EEF = 32,
robot_interaction::InteractionStyle::FIXED = 64,
robot_interaction::InteractionStyle::POSITION = POSITION_ARROWS | POSITION_SPHERE | POSITION_EEF,
robot_interaction::InteractionStyle::ORIENTATION = ORIENTATION_CIRCLES | ORIENTATION_SPHERE | ORIENTATION_EEF,
robot_interaction::InteractionStyle::SIX_DOF = POSITION | ORIENTATION,
robot_interaction::InteractionStyle::SIX_DOF_SPHERE = POSITION_SPHERE | ORIENTATION_SPHERE,
robot_interaction::InteractionStyle::POSITION_NOSPHERE = POSITION_ARROWS | POSITION_EEF,
robot_interaction::InteractionStyle::ORIENTATION_NOSPHERE = ORIENTATION_CIRCLES | ORIENTATION_EEF,
robot_interaction::InteractionStyle::SIX_DOF_NOSPHERE = POSITION_NOSPHERE | ORIENTATION_NOSPHERE
} |