#include <trajectory.h>
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< GripperMarkerPtr > | waypoint_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_ |
Definition at line 44 of file trajectory.h.
enum benchmark_tool::Trajectory::ControlMarkerModeType [private] |
Definition at line 151 of file trajectory.h.
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 49 of file trajectory.cpp.
benchmark_tool::Trajectory::~Trajectory | ( | ) | [inline] |
Definition at line 121 of file trajectory.h.
void benchmark_tool::Trajectory::connectControlMarker | ( | ) | [protected] |
Definition at line 134 of file trajectory.cpp.
void benchmark_tool::Trajectory::connectEndMarker | ( | ) | [protected] |
Definition at line 148 of file trajectory.cpp.
void benchmark_tool::Trajectory::connectHandMarker | ( | ) | [protected] |
Definition at line 139 of file trajectory.cpp.
void benchmark_tool::Trajectory::connectStartMarker | ( | ) | [protected] |
Definition at line 144 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 58 of file trajectory.cpp.
void benchmark_tool::Trajectory::createEndMarker | ( | ) | [protected] |
Definition at line 118 of file trajectory.cpp.
void benchmark_tool::Trajectory::createHandMarker | ( | ) | [protected] |
Definition at line 88 of file trajectory.cpp.
void benchmark_tool::Trajectory::createStartMarker | ( | ) | [protected] |
Definition at line 102 of file trajectory.cpp.
void benchmark_tool::Trajectory::editControlFrame | ( | ) | [private] |
Definition at line 266 of file trajectory.cpp.
void benchmark_tool::Trajectory::endMarkerFeedback | ( | visualization_msgs::InteractiveMarkerFeedback & | feedback | ) | [slot] |
Definition at line 326 of file trajectory.cpp.
void benchmark_tool::Trajectory::fixControlFrame | ( | ) | [private] |
Definition at line 296 of file trajectory.cpp.
void benchmark_tool::Trajectory::handMarkerFeedback | ( | visualization_msgs::InteractiveMarkerFeedback & | feedback | ) | [slot] |
Definition at line 330 of file trajectory.cpp.
void benchmark_tool::Trajectory::hide | ( | void | ) | [inline] |
Definition at line 89 of file trajectory.h.
void benchmark_tool::Trajectory::rebuildWayPointMarkers | ( | ) | [protected] |
Definition at line 153 of file trajectory.cpp.
void benchmark_tool::Trajectory::setControlMarker | ( | const GripperMarkerPtr | control_marker | ) |
void benchmark_tool::Trajectory::setNumberOfWaypoints | ( | unsigned int | n | ) | [inline] |
Definition at line 80 of file trajectory.h.
void benchmark_tool::Trajectory::show | ( | Ogre::SceneNode * | scene_node, |
rviz::DisplayContext * | context | ||
) | [inline] |
Definition at line 105 of file trajectory.h.
void benchmark_tool::Trajectory::startMarkerFeedback | ( | visualization_msgs::InteractiveMarkerFeedback & | feedback | ) | [slot] |
Definition at line 322 of file trajectory.cpp.
void benchmark_tool::Trajectory::trajectoryMarkerFeedback | ( | visualization_msgs::InteractiveMarkerFeedback & | feedback | ) | [slot] |
Definition at line 196 of file trajectory.cpp.
Definition at line 65 of file trajectory.h.
Eigen::Affine3d benchmark_tool::Trajectory::control_marker_drag_start_pose [private] |
Definition at line 145 of file trajectory.h.
Eigen::Affine3d benchmark_tool::Trajectory::control_marker_end_pose |
Definition at line 71 of file trajectory.h.
Definition at line 152 of file trajectory.h.
Eigen::Affine3d benchmark_tool::Trajectory::control_marker_start_pose |
Definition at line 70 of file trajectory.h.
bool benchmark_tool::Trajectory::dragging_ [private] |
Definition at line 147 of file trajectory.h.
Definition at line 67 of file trajectory.h.
Definition at line 66 of file trajectory.h.
Eigen::Affine3d benchmark_tool::Trajectory::hand_marker_start_pose [private] |
Definition at line 144 of file trajectory.h.
unsigned int benchmark_tool::Trajectory::nwaypoints_ [private] |
Definition at line 149 of file trajectory.h.
Definition at line 67 of file trajectory.h.
const int benchmark_tool::Trajectory::TRAJECTORY_EDIT_CONTROL_FRAME = 3 [static] |
Definition at line 57 of file trajectory.h.
const std::string benchmark_tool::Trajectory::TRAJECTORY_EDIT_CONTROL_FRAME_STRING = "Edit control frame" [static] |
Definition at line 62 of file trajectory.h.
const int benchmark_tool::Trajectory::TRAJECTORY_FIX_CONTROL_FRAME = 4 [static] |
Definition at line 58 of file trajectory.h.
const std::string benchmark_tool::Trajectory::TRAJECTORY_FIX_CONTROL_FRAME_STRING = "Fix control frame" [static] |
Definition at line 63 of file trajectory.h.
const int benchmark_tool::Trajectory::TRAJECTORY_SET_END_POSE = 2 [static] |
Definition at line 56 of file trajectory.h.
const std::string benchmark_tool::Trajectory::TRAJECTORY_SET_END_POSE_STRING = "Set end pose" [static] |
Definition at line 61 of file trajectory.h.
const int benchmark_tool::Trajectory::TRAJECTORY_SET_START_POSE = 1 [static] |
Definition at line 55 of file trajectory.h.
const std::string benchmark_tool::Trajectory::TRAJECTORY_SET_START_POSE_STRING = "Set start pose" [static] |
Definition at line 60 of file trajectory.h.
Definition at line 68 of file trajectory.h.