rviz::PoseDisplay Class Reference

Accumulates and displays the pose from a geometry_msgs::PoseStamped message. More...

#include <pose_display.h>

Inheritance diagram for rviz::PoseDisplay:
Inheritance graph
[legend]

List of all members.

Public Types

enum  Shape { Arrow, Axes }

Public Member Functions

virtual void createProperties ()
 Called from setPropertyManager, gives the display a chance to create some properties immediately.
virtual void fixedFrameChanged ()
 Called from within setFixedFrame, notifying child classes that the fixed frame has changed.
float getAlpha ()
float getAxesLength ()
float getAxesRadius ()
const ColorgetColor ()
float getHeadLength ()
float getHeadRadius ()
float getShaftLength ()
float getShaftRadius ()
int getShape ()
const std::string & getTopic ()
 PoseDisplay (const std::string &name, VisualizationManager *manager)
virtual void reset ()
 Called to tell the display to clear its state.
void setAlpha (float a)
void setAxesLength (float l)
void setAxesRadius (float r)
void setColor (const Color &color)
void setHeadLength (float l)
void setHeadRadius (float r)
void setShaftLength (float l)
void setShaftRadius (float r)
void setShape (int shape)
void setTopic (const std::string &topic)
virtual void targetFrameChanged ()
 Called from within setTargetFrame, notifying child classes that the target frame has changed.
virtual void update (float wall_dt, float ros_dt)
 Called periodically by the visualization panel.
virtual ~PoseDisplay ()

Protected Member Functions

void clear ()
void createShapeProperties ()
void incomingMessage (const geometry_msgs::PoseStamped::ConstPtr &message)
virtual void onDisable ()
 Derived classes override this to do the actual work of disabling themselves.
virtual void onEnable ()
 Derived classes override this to do the actual work of enabling themselves.
void setVisibility ()
void subscribe ()
void unsubscribe ()

Protected Attributes

float alpha_
FloatPropertyWPtr alpha_property_
ogre_tools::Arrow * arrow_
ogre_tools::Axes * axes_
float axes_length_
FloatPropertyWPtr axes_length_property_
float axes_radius_
FloatPropertyWPtr axes_radius_property_
CollObjectHandle coll_
PoseDisplaySelectionHandlerPtr coll_handler_
Color color_
ColorPropertyWPtr color_property_
Shape current_shape_
float head_length_
FloatPropertyWPtr head_length_property_
float head_radius_
FloatPropertyWPtr head_radius_property_
geometry_msgs::PoseStampedConstPtr latest_message_
uint32_t messages_received_
Ogre::SceneNode * scene_node_
float shaft_length_
FloatPropertyWPtr shaft_length_property_
float shaft_radius_
FloatPropertyWPtr shaft_radius_property_
CategoryPropertyWPtr shape_category_
EnumPropertyWPtr shape_property_
message_filters::Subscriber
< geometry_msgs::PoseStamped > 
sub_
tf::MessageFilter
< geometry_msgs::PoseStamped > 
tf_filter_
std::string topic_
ROSTopicStringPropertyWPtr topic_property_

Detailed Description

Accumulates and displays the pose from a geometry_msgs::PoseStamped message.

Definition at line 69 of file pose_display.h.


Member Enumeration Documentation

Enumerator:
Arrow 
Axes 

Definition at line 72 of file pose_display.h.


Constructor & Destructor Documentation

rviz::PoseDisplay::PoseDisplay ( const std::string &  name,
VisualizationManager manager 
)

Definition at line 94 of file pose_display.cpp.

rviz::PoseDisplay::~PoseDisplay (  )  [virtual]

Definition at line 131 of file pose_display.cpp.


Member Function Documentation

void rviz::PoseDisplay::clear (  )  [protected]

Definition at line 144 of file pose_display.cpp.

void rviz::PoseDisplay::createProperties (  )  [virtual]

Called from setPropertyManager, gives the display a chance to create some properties immediately.

Once this function is called, the property_manager_ member is valid and will stay valid

Reimplemented from rviz::Display.

Definition at line 344 of file pose_display.cpp.

void rviz::PoseDisplay::createShapeProperties (  )  [protected]

Definition at line 294 of file pose_display.cpp.

void rviz::PoseDisplay::fixedFrameChanged (  )  [virtual]

Called from within setFixedFrame, notifying child classes that the fixed frame has changed.

Implements rviz::Display.

Definition at line 366 of file pose_display.cpp.

float rviz::PoseDisplay::getAlpha (  )  [inline]

Definition at line 91 of file pose_display.h.

float rviz::PoseDisplay::getAxesLength (  )  [inline]

Definition at line 107 of file pose_display.h.

float rviz::PoseDisplay::getAxesRadius (  )  [inline]

Definition at line 105 of file pose_display.h.

const Color& rviz::PoseDisplay::getColor (  )  [inline]

Definition at line 85 of file pose_display.h.

float rviz::PoseDisplay::getHeadLength (  )  [inline]

Definition at line 97 of file pose_display.h.

float rviz::PoseDisplay::getHeadRadius (  )  [inline]

Definition at line 95 of file pose_display.h.

float rviz::PoseDisplay::getShaftLength (  )  [inline]

Definition at line 101 of file pose_display.h.

float rviz::PoseDisplay::getShaftRadius (  )  [inline]

Definition at line 99 of file pose_display.h.

int rviz::PoseDisplay::getShape (  )  [inline]

Definition at line 88 of file pose_display.h.

const std::string& rviz::PoseDisplay::getTopic (  )  [inline]

Definition at line 82 of file pose_display.h.

void rviz::PoseDisplay::incomingMessage ( const geometry_msgs::PoseStamped::ConstPtr &  message  )  [protected]

Definition at line 376 of file pose_display.cpp.

void rviz::PoseDisplay::onDisable (  )  [protected, virtual]

Derived classes override this to do the actual work of disabling themselves.

Implements rviz::Display.

Definition at line 287 of file pose_display.cpp.

void rviz::PoseDisplay::onEnable (  )  [protected, virtual]

Derived classes override this to do the actual work of enabling themselves.

Implements rviz::Display.

Definition at line 280 of file pose_display.cpp.

void rviz::PoseDisplay::reset (  )  [virtual]

Called to tell the display to clear its state.

Reimplemented from rviz::Display.

Definition at line 409 of file pose_display.cpp.

void rviz::PoseDisplay::setAlpha ( float  a  ) 

Definition at line 177 of file pose_display.cpp.

void rviz::PoseDisplay::setAxesLength ( float  l  ) 

Definition at line 224 of file pose_display.cpp.

void rviz::PoseDisplay::setAxesRadius ( float  r  ) 

Definition at line 217 of file pose_display.cpp.

void rviz::PoseDisplay::setColor ( const Color color  ) 

Definition at line 165 of file pose_display.cpp.

void rviz::PoseDisplay::setHeadLength ( float  l  ) 

Definition at line 196 of file pose_display.cpp.

void rviz::PoseDisplay::setHeadRadius ( float  r  ) 

Definition at line 189 of file pose_display.cpp.

void rviz::PoseDisplay::setShaftLength ( float  l  ) 

Definition at line 210 of file pose_display.cpp.

void rviz::PoseDisplay::setShaftRadius ( float  r  ) 

Definition at line 203 of file pose_display.cpp.

void rviz::PoseDisplay::setShape ( int  shape  ) 

Definition at line 231 of file pose_display.cpp.

void rviz::PoseDisplay::setTopic ( const std::string &  topic  ) 

Definition at line 154 of file pose_display.cpp.

void rviz::PoseDisplay::setVisibility (  )  [protected]

Definition at line 244 of file pose_display.cpp.

void rviz::PoseDisplay::subscribe (  )  [protected]

Definition at line 265 of file pose_display.cpp.

void rviz::PoseDisplay::targetFrameChanged (  )  [virtual]

Called from within setTargetFrame, notifying child classes that the target frame has changed.

Implements rviz::Display.

Definition at line 362 of file pose_display.cpp.

void rviz::PoseDisplay::unsubscribe (  )  [protected]

Definition at line 275 of file pose_display.cpp.

void rviz::PoseDisplay::update ( float  wall_dt,
float  ros_dt 
) [virtual]

Called periodically by the visualization panel.

Parameters:
dt Wall-clock time, in seconds, since the last time the update list was run through.

Reimplemented from rviz::Display.

Definition at line 372 of file pose_display.cpp.


Member Data Documentation

float rviz::PoseDisplay::alpha_ [protected]

Definition at line 132 of file pose_display.h.

FloatPropertyWPtr rviz::PoseDisplay::alpha_property_ [protected]

Definition at line 163 of file pose_display.h.

ogre_tools::Arrow* rviz::PoseDisplay::arrow_ [protected]

Definition at line 145 of file pose_display.h.

ogre_tools::Axes* rviz::PoseDisplay::axes_ [protected]

Definition at line 146 of file pose_display.h.

Definition at line 142 of file pose_display.h.

FloatPropertyWPtr rviz::PoseDisplay::axes_length_property_ [protected]

Definition at line 170 of file pose_display.h.

Definition at line 143 of file pose_display.h.

FloatPropertyWPtr rviz::PoseDisplay::axes_radius_property_ [protected]

Definition at line 171 of file pose_display.h.

Definition at line 147 of file pose_display.h.

Definition at line 148 of file pose_display.h.

Definition at line 131 of file pose_display.h.

ColorPropertyWPtr rviz::PoseDisplay::color_property_ [protected]

Definition at line 162 of file pose_display.h.

Definition at line 133 of file pose_display.h.

Definition at line 137 of file pose_display.h.

FloatPropertyWPtr rviz::PoseDisplay::head_length_property_ [protected]

Definition at line 166 of file pose_display.h.

Definition at line 136 of file pose_display.h.

FloatPropertyWPtr rviz::PoseDisplay::head_radius_property_ [protected]

Definition at line 165 of file pose_display.h.

geometry_msgs::PoseStampedConstPtr rviz::PoseDisplay::latest_message_ [protected]

Definition at line 156 of file pose_display.h.

Definition at line 150 of file pose_display.h.

Ogre::SceneNode* rviz::PoseDisplay::scene_node_ [protected]

Definition at line 152 of file pose_display.h.

Definition at line 139 of file pose_display.h.

FloatPropertyWPtr rviz::PoseDisplay::shaft_length_property_ [protected]

Definition at line 168 of file pose_display.h.

Definition at line 138 of file pose_display.h.

FloatPropertyWPtr rviz::PoseDisplay::shaft_radius_property_ [protected]

Definition at line 167 of file pose_display.h.

CategoryPropertyWPtr rviz::PoseDisplay::shape_category_ [protected]

Definition at line 160 of file pose_display.h.

EnumPropertyWPtr rviz::PoseDisplay::shape_property_ [protected]

Definition at line 159 of file pose_display.h.

message_filters::Subscriber<geometry_msgs::PoseStamped> rviz::PoseDisplay::sub_ [protected]

Definition at line 154 of file pose_display.h.

tf::MessageFilter<geometry_msgs::PoseStamped> rviz::PoseDisplay::tf_filter_ [protected]

Definition at line 155 of file pose_display.h.

std::string rviz::PoseDisplay::topic_ [protected]

Definition at line 130 of file pose_display.h.

ROSTopicStringPropertyWPtr rviz::PoseDisplay::topic_property_ [protected]

Definition at line 158 of file pose_display.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


rviz
Author(s): Josh Faust
autogenerated on Fri Jan 11 09:36:34 2013