Public Slots | Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | Private Types | Private Member Functions | Private Attributes
benchmark_tool::Trajectory Class Reference

#include <trajectory.h>

List of all members.

Public Slots

void endMarkerFeedback (visualization_msgs::InteractiveMarkerFeedback &feedback)
void handMarkerFeedback (visualization_msgs::InteractiveMarkerFeedback &feedback)
void startMarkerFeedback (visualization_msgs::InteractiveMarkerFeedback &feedback)
void trajectoryMarkerFeedback (visualization_msgs::InteractiveMarkerFeedback &feedback)

Public Member Functions

void hide ()
void setControlMarker (const GripperMarkerPtr control_marker)
void setNumberOfWaypoints (unsigned int n)
void show (Ogre::SceneNode *scene_node, rviz::DisplayContext *context)
 Trajectory (const robot_state::RobotState &robot_state, Ogre::SceneNode *parent_node, rviz::DisplayContext *context, const std::string &name, const std::string &frame_id, const robot_interaction::RobotInteraction::EndEffector &eef, const geometry_msgs::Pose &pose, double scale, const GripperMarker::GripperMarkerState &state, unsigned int nwaypoints, bool is_selected=true, bool visible_x=true, bool visible_y=true, bool visible_z=true)
 ~Trajectory ()

Public Attributes

GripperMarkerPtr control_marker
Eigen::Affine3d control_marker_end_pose
Eigen::Affine3d control_marker_start_pose
GripperMarkerPtr end_marker
GripperMarkerPtr hand_marker
GripperMarkerPtr start_marker
std::vector< GripperMarkerPtrwaypoint_markers

Static Public Attributes

static const int TRAJECTORY_EDIT_CONTROL_FRAME = 3
static const std::string TRAJECTORY_EDIT_CONTROL_FRAME_STRING = "Edit control frame"
static const int TRAJECTORY_FIX_CONTROL_FRAME = 4
static const std::string TRAJECTORY_FIX_CONTROL_FRAME_STRING = "Fix control frame"
static const int TRAJECTORY_SET_END_POSE = 2
static const std::string TRAJECTORY_SET_END_POSE_STRING = "Set end pose"
static const int TRAJECTORY_SET_START_POSE = 1
static const std::string TRAJECTORY_SET_START_POSE_STRING = "Set start pose"

Protected Member Functions

void connectControlMarker ()
void connectEndMarker ()
void connectHandMarker ()
void connectStartMarker ()
void createControlMarker (const robot_state::RobotState &robot_state, Ogre::SceneNode *parent_node, rviz::DisplayContext *context, const std::string &name, const std::string &frame_id, const robot_interaction::RobotInteraction::EndEffector &eef, const geometry_msgs::Pose &pose, double scale, const GripperMarker::GripperMarkerState &state, bool is_selected=true, bool visible_x=true, bool visible_y=true, bool visible_z=true)
void createEndMarker ()
void createHandMarker ()
void createStartMarker ()
void rebuildWayPointMarkers ()

Private Types

enum  ControlMarkerModeType { CONTROL_MARKER_FLOATING, CONTROL_MARKER_FIXED }

Private Member Functions

void editControlFrame ()
void fixControlFrame ()

Private Attributes

Eigen::Affine3d control_marker_drag_start_pose
ControlMarkerModeType control_marker_mode_
bool dragging_
Eigen::Affine3d hand_marker_start_pose
unsigned int nwaypoints_

Detailed Description

Definition at line 49 of file trajectory.h.


Member Enumeration Documentation

Enumerator:
CONTROL_MARKER_FLOATING 
CONTROL_MARKER_FIXED 

Definition at line 156 of file trajectory.h.


Constructor & Destructor Documentation

benchmark_tool::Trajectory::Trajectory ( const robot_state::RobotState &  robot_state,
Ogre::SceneNode *  parent_node,
rviz::DisplayContext context,
const std::string &  name,
const std::string &  frame_id,
const robot_interaction::RobotInteraction::EndEffector eef,
const geometry_msgs::Pose pose,
double  scale,
const GripperMarker::GripperMarkerState state,
unsigned int  nwaypoints,
bool  is_selected = true,
bool  visible_x = true,
bool  visible_y = true,
bool  visible_z = true 
)

Definition at line 54 of file trajectory.cpp.

Definition at line 126 of file trajectory.h.


Member Function Documentation

Definition at line 139 of file trajectory.cpp.

Definition at line 153 of file trajectory.cpp.

Definition at line 144 of file trajectory.cpp.

Definition at line 149 of file trajectory.cpp.

void benchmark_tool::Trajectory::createControlMarker ( const robot_state::RobotState &  robot_state,
Ogre::SceneNode *  parent_node,
rviz::DisplayContext context,
const std::string &  name,
const std::string &  frame_id,
const robot_interaction::RobotInteraction::EndEffector eef,
const geometry_msgs::Pose pose,
double  scale,
const GripperMarker::GripperMarkerState state,
bool  is_selected = true,
bool  visible_x = true,
bool  visible_y = true,
bool  visible_z = true 
) [protected]

Definition at line 63 of file trajectory.cpp.

Definition at line 123 of file trajectory.cpp.

Definition at line 93 of file trajectory.cpp.

Definition at line 107 of file trajectory.cpp.

Definition at line 271 of file trajectory.cpp.

void benchmark_tool::Trajectory::endMarkerFeedback ( visualization_msgs::InteractiveMarkerFeedback &  feedback) [slot]

Definition at line 331 of file trajectory.cpp.

Definition at line 301 of file trajectory.cpp.

void benchmark_tool::Trajectory::handMarkerFeedback ( visualization_msgs::InteractiveMarkerFeedback &  feedback) [slot]

Definition at line 335 of file trajectory.cpp.

void benchmark_tool::Trajectory::hide ( void  ) [inline]

Definition at line 94 of file trajectory.h.

Definition at line 158 of file trajectory.cpp.

void benchmark_tool::Trajectory::setNumberOfWaypoints ( unsigned int  n) [inline]

Definition at line 85 of file trajectory.h.

void benchmark_tool::Trajectory::show ( Ogre::SceneNode *  scene_node,
rviz::DisplayContext context 
) [inline]

Definition at line 110 of file trajectory.h.

void benchmark_tool::Trajectory::startMarkerFeedback ( visualization_msgs::InteractiveMarkerFeedback &  feedback) [slot]

Definition at line 327 of file trajectory.cpp.

void benchmark_tool::Trajectory::trajectoryMarkerFeedback ( visualization_msgs::InteractiveMarkerFeedback &  feedback) [slot]

Definition at line 201 of file trajectory.cpp.


Member Data Documentation

Definition at line 70 of file trajectory.h.

Definition at line 150 of file trajectory.h.

Definition at line 76 of file trajectory.h.

Definition at line 157 of file trajectory.h.

Definition at line 75 of file trajectory.h.

Definition at line 152 of file trajectory.h.

Definition at line 72 of file trajectory.h.

Definition at line 71 of file trajectory.h.

Definition at line 149 of file trajectory.h.

Definition at line 154 of file trajectory.h.

Definition at line 72 of file trajectory.h.

Definition at line 62 of file trajectory.h.

const std::string benchmark_tool::Trajectory::TRAJECTORY_EDIT_CONTROL_FRAME_STRING = "Edit control frame" [static]

Definition at line 67 of file trajectory.h.

Definition at line 63 of file trajectory.h.

const std::string benchmark_tool::Trajectory::TRAJECTORY_FIX_CONTROL_FRAME_STRING = "Fix control frame" [static]

Definition at line 68 of file trajectory.h.

Definition at line 61 of file trajectory.h.

const std::string benchmark_tool::Trajectory::TRAJECTORY_SET_END_POSE_STRING = "Set end pose" [static]

Definition at line 66 of file trajectory.h.

Definition at line 60 of file trajectory.h.

Definition at line 65 of file trajectory.h.

Definition at line 73 of file trajectory.h.


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


benchmarks_gui
Author(s): Mario Prats
autogenerated on Wed Aug 26 2015 12:44:27