Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
benchmark_tool::FrameMarker Class Reference

#include <frame_marker.h>

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

List of all members.

Public Member Functions

void connect (const QObject *receiver, const char *method)
 FrameMarker (const FrameMarker &frame_marker)
 FrameMarker (Ogre::SceneNode *parent_node, rviz::DisplayContext *context, const std::string &name, const std::string &frame_id, const geometry_msgs::Pose &pose, double scale, const std_msgs::ColorRGBA &color, bool is_selected=false, bool visible_x=true, bool visible_y=true, bool visible_z=true)
 FrameMarker (Ogre::SceneNode *parent_node, rviz::DisplayContext *context, const std::string &name, const std::string &frame_id, const geometry_msgs::Pose &pose, double scale, const float color[4], bool is_selected=false, bool visible_x=true, bool visible_y=true, bool visible_z=true)
const std::string & getName ()
virtual void getOrientation (geometry_msgs::Quaternion &orientation)
virtual void getPose (Eigen::Affine3d &pose)
virtual void getPosition (geometry_msgs::Point &position)
virtual void hide (void)
virtual void hideDescription ()
bool isSelected (void)
bool isVisible ()
virtual void select (void)
virtual void setAxisVisibility (bool x, bool y, bool z)
virtual void setColor (float r, float g, float b, float a)
virtual void setMenu (std::vector< visualization_msgs::MenuEntry > entries)
void setName (const std::string &name)
virtual void setPose (Eigen::Affine3d &pose)
virtual void show (Ogre::SceneNode *scene_node, rviz::DisplayContext *context)
virtual void showDescription (const std::string &description)
virtual void unselect (void)
virtual void updateMarker (void)
virtual ~FrameMarker ()

Public Attributes

boost::shared_ptr
< rviz::InteractiveMarker
imarker
visualization_msgs::InteractiveMarker imarker_msg

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)
virtual void rebuild ()

Protected Attributes

std_msgs::ColorRGBA color_
rviz::DisplayContextcontext_
std::vector
< visualization_msgs::MenuEntry > 
menu_entries_
Ogre::Quaternion orientation_
Ogre::SceneNode * parent_node_
Ogre::Vector3 position_
const QObject * receiver_
const char * receiver_method_
bool selected_
bool visible_x_
bool visible_y_
bool visible_z_

Detailed Description

Base class for interactive markers displaying a coordinate system A basic coordinate system is composed its three axis and a small sphere at the origin The frame can be selected/unselected. When selected, controls for positioning are displayed

Definition at line 60 of file frame_marker.h.


Constructor & Destructor Documentation

benchmark_tool::FrameMarker::FrameMarker ( const FrameMarker frame_marker) [inline]

Copy constructor

Definition at line 67 of file frame_marker.h.

benchmark_tool::FrameMarker::FrameMarker ( Ogre::SceneNode *  parent_node,
rviz::DisplayContext context,
const std::string &  name,
const std::string &  frame_id,
const geometry_msgs::Pose pose,
double  scale,
const std_msgs::ColorRGBA &  color,
bool  is_selected = false,
bool  visible_x = true,
bool  visible_y = true,
bool  visible_z = true 
)

Constructor

Parameters:
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
posethe desired pose of the coordinate system
scalethe scale of the coordinate system
colorthe color of the sphere drawn at the origin of the frame
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 55 of file frame_marker.cpp.

benchmark_tool::FrameMarker::FrameMarker ( Ogre::SceneNode *  parent_node,
rviz::DisplayContext context,
const std::string &  name,
const std::string &  frame_id,
const geometry_msgs::Pose pose,
double  scale,
const float  color[4],
bool  is_selected = false,
bool  visible_x = true,
bool  visible_y = true,
bool  visible_z = true 
)

Definition at line 71 of file frame_marker.cpp.

virtual benchmark_tool::FrameMarker::~FrameMarker ( ) [inline, virtual]

Definition at line 168 of file frame_marker.h.


Member Function Documentation

void benchmark_tool::FrameMarker::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 in benchmark_tool::GripperMarker.

Definition at line 229 of file frame_marker.cpp.

void benchmark_tool::FrameMarker::connect ( const QObject *  receiver,
const char *  method 
) [inline]

Definition at line 161 of file frame_marker.h.

const std::string& benchmark_tool::FrameMarker::getName ( void  ) [inline]

Definition at line 141 of file frame_marker.h.

void benchmark_tool::FrameMarker::getOrientation ( geometry_msgs::Quaternion &  orientation) [virtual]

Definition at line 143 of file frame_marker.cpp.

void benchmark_tool::FrameMarker::getPose ( Eigen::Affine3d &  pose) [virtual]

Definition at line 161 of file frame_marker.cpp.

Definition at line 127 of file frame_marker.cpp.

void benchmark_tool::FrameMarker::hide ( void  ) [virtual]

Definition at line 90 of file frame_marker.cpp.

Definition at line 122 of file frame_marker.cpp.

bool benchmark_tool::FrameMarker::isSelected ( void  ) [inline]

Definition at line 151 of file frame_marker.h.

Definition at line 156 of file frame_marker.h.

void benchmark_tool::FrameMarker::rebuild ( ) [protected, virtual]

Definition at line 221 of file frame_marker.cpp.

void benchmark_tool::FrameMarker::select ( void  ) [virtual]

Definition at line 209 of file frame_marker.cpp.

virtual void benchmark_tool::FrameMarker::setAxisVisibility ( bool  x,
bool  y,
bool  z 
) [inline, virtual]

Definition at line 117 of file frame_marker.h.

void benchmark_tool::FrameMarker::setColor ( float  r,
float  g,
float  b,
float  a 
) [virtual]

Definition at line 177 of file frame_marker.cpp.

virtual void benchmark_tool::FrameMarker::setMenu ( std::vector< visualization_msgs::MenuEntry >  entries) [inline, virtual]

Definition at line 135 of file frame_marker.h.

void benchmark_tool::FrameMarker::setName ( const std::string &  name) [inline]

Definition at line 146 of file frame_marker.h.

void benchmark_tool::FrameMarker::setPose ( Eigen::Affine3d &  pose) [virtual]

Definition at line 170 of file frame_marker.cpp.

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

Definition at line 100 of file frame_marker.cpp.

void benchmark_tool::FrameMarker::showDescription ( const std::string &  description) [virtual]

Definition at line 108 of file frame_marker.cpp.

void benchmark_tool::FrameMarker::unselect ( void  ) [virtual]

Definition at line 215 of file frame_marker.cpp.

virtual void benchmark_tool::FrameMarker::updateMarker ( void  ) [inline, virtual]

Definition at line 106 of file frame_marker.h.


Member Data Documentation

std_msgs::ColorRGBA benchmark_tool::FrameMarker::color_ [protected]

Definition at line 182 of file frame_marker.h.

Definition at line 178 of file frame_marker.h.

Definition at line 64 of file frame_marker.h.

visualization_msgs::InteractiveMarker benchmark_tool::FrameMarker::imarker_msg

Definition at line 63 of file frame_marker.h.

std::vector<visualization_msgs::MenuEntry> benchmark_tool::FrameMarker::menu_entries_ [protected]

Definition at line 175 of file frame_marker.h.

Ogre::Quaternion benchmark_tool::FrameMarker::orientation_ [protected]

Definition at line 185 of file frame_marker.h.

Ogre::SceneNode* benchmark_tool::FrameMarker::parent_node_ [protected]

Definition at line 177 of file frame_marker.h.

Ogre::Vector3 benchmark_tool::FrameMarker::position_ [protected]

Definition at line 184 of file frame_marker.h.

const QObject* benchmark_tool::FrameMarker::receiver_ [protected]

Definition at line 187 of file frame_marker.h.

Definition at line 188 of file frame_marker.h.

Definition at line 180 of file frame_marker.h.

Definition at line 181 of file frame_marker.h.

Definition at line 181 of file frame_marker.h.

Definition at line 181 of file frame_marker.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