Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes
benchmark_tool::GripperMarker Class Reference

#include <frame_marker.h>

Inheritance diagram for benchmark_tool::GripperMarker:
Inheritance graph
[legend]

List of all members.

Public Types

enum  GripperMarkerState {
  NOT_TESTED, PROCESSING, REACHABLE, NOT_REACHABLE,
  IN_COLLISION
}

Public Member Functions

const
robot_interaction::RobotInteraction::EndEffector 
getEndEffector ()
const robot_state::RobotStategetRobotState ()
const GripperMarkerStategetState ()
 GripperMarker (const GripperMarker &gripper_marker)
 GripperMarker (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 GripperMarkerState &state, bool is_selected=false, bool visible_x=true, bool visible_y=true, bool visible_z=true)
virtual void select (bool display_gripper_mesh=true)
void setEndEffector (const robot_interaction::RobotInteraction::EndEffector &eef)
void setRobotState (const robot_state::RobotState &robot_state)
virtual void setState (const GripperMarkerState &state)
virtual void unselect (bool display_gripper_mesh=false)

Protected Member Functions

virtual void buildFrom (const std::string &name, const std::string &frame_id, const geometry_msgs::Pose &pose, double scale, const std_msgs::ColorRGBA &color)
const float * stateToColor (const GripperMarkerState &state)

Protected Attributes

bool display_gripper_mesh_
robot_interaction::RobotInteraction::EndEffector eef_
const robot_state::RobotStaterobot_state_
GripperMarkerState state_

Static Protected Attributes

static const float GOAL_COLLISION_COLOR [4] = { 1.0, 1.0, 0.0, 1.0}
static const float GOAL_NOT_REACHABLE_COLOR [4] = { 1.0, 0.0, 0.0, 1.0}
static const float GOAL_NOT_TESTED_COLOR [4] = { 0.75, 0.75, 0.75, 1.0}
static const float GOAL_PROCESSING_COLOR [4] = { 0.9, 0.9, 0.9, 1.0}
static const float GOAL_REACHABLE_COLOR [4] = { 0.0, 1.0, 0.0, 1.0}

Detailed Description

A special FrameMarker that displays the robot end-effector mesh when selected. It also allows defining different states (rechable, not-reachable, in-collision, not-tested and processing) and will switch the mesh color according to these.

Definition at line 190 of file frame_marker.h.


Member Enumeration Documentation

Enumerator:
NOT_TESTED 
PROCESSING 
REACHABLE 
NOT_REACHABLE 
IN_COLLISION 

Definition at line 193 of file frame_marker.h.


Constructor & Destructor Documentation

benchmark_tool::GripperMarker::GripperMarker ( const GripperMarker gripper_marker) [inline]

Copy constructor

Definition at line 199 of file frame_marker.h.

benchmark_tool::GripperMarker::GripperMarker ( 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 GripperMarkerState state,
bool  is_selected = false,
bool  visible_x = true,
bool  visible_y = true,
bool  visible_z = true 
)

Constructor

Parameters:
robot_statethe kinematic state of the robot
parent_nodethe Ogre node that will hold this interactive marker
contextthe display context
namethe name for the interactive marker
frame_idthe frame_id the interactive marker is given relative to
eefthe robot_interaction end effector description
posethe desired pose of the coordinate system
scalethe scale of the coordinate system
statethe default state of the GripperMarker
is_selectedwhether this frame marker is selected or not by default. When selected, controls are displayed
visible_x,visible_y,visible_zdefine the visibility of each axis

Definition at line 322 of file frame_marker.cpp.


Member Function Documentation

void benchmark_tool::GripperMarker::buildFrom ( const std::string &  name,
const std::string &  frame_id,
const geometry_msgs::Pose pose,
double  scale,
const std_msgs::ColorRGBA &  color 
) [protected, virtual]

Reimplemented from benchmark_tool::FrameMarker.

Definition at line 345 of file frame_marker.cpp.

Definition at line 259 of file frame_marker.h.

Definition at line 249 of file frame_marker.h.

Definition at line 239 of file frame_marker.h.

void benchmark_tool::GripperMarker::select ( bool  display_gripper_mesh = true) [virtual]

Definition at line 333 of file frame_marker.cpp.

Definition at line 254 of file frame_marker.h.

Definition at line 244 of file frame_marker.h.

virtual void benchmark_tool::GripperMarker::setState ( const GripperMarkerState state) [inline, virtual]

Definition at line 229 of file frame_marker.h.

const float * benchmark_tool::GripperMarker::stateToColor ( const GripperMarkerState state) [protected]

Definition at line 470 of file frame_marker.cpp.

void benchmark_tool::GripperMarker::unselect ( bool  display_gripper_mesh = false) [virtual]

Definition at line 339 of file frame_marker.cpp.


Member Data Documentation

Definition at line 278 of file frame_marker.h.

Definition at line 276 of file frame_marker.h.

const float benchmark_tool::GripperMarker::GOAL_COLLISION_COLOR = { 1.0, 1.0, 0.0, 1.0} [static, protected]

Definition at line 269 of file frame_marker.h.

const float benchmark_tool::GripperMarker::GOAL_NOT_REACHABLE_COLOR = { 1.0, 0.0, 0.0, 1.0} [static, protected]

Definition at line 267 of file frame_marker.h.

const float benchmark_tool::GripperMarker::GOAL_NOT_TESTED_COLOR = { 0.75, 0.75, 0.75, 1.0} [static, protected]

Definition at line 265 of file frame_marker.h.

const float benchmark_tool::GripperMarker::GOAL_PROCESSING_COLOR = { 0.9, 0.9, 0.9, 1.0} [static, protected]

Definition at line 266 of file frame_marker.h.

const float benchmark_tool::GripperMarker::GOAL_REACHABLE_COLOR = { 0.0, 1.0, 0.0, 1.0} [static, protected]

Definition at line 268 of file frame_marker.h.

Definition at line 275 of file frame_marker.h.

Definition at line 279 of file frame_marker.h.


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


benchmarks_gui
Author(s): Mario Prats
autogenerated on Mon Oct 6 2014 02:34:25