$search

rviz::GridCellsDisplay Class Reference

Displays a nav_msgs::GridCells message. More...

#include <grid_cells_display.h>

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

List of all members.

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 ()
const ColorgetColor ()
const std::string & getTopic ()
virtual const char * getType () const
 GridCellsDisplay (const std::string &name, VisualizationManager *manager)
virtual void reset ()
 Called to tell the display to clear its state.
void setAlpha (float alpha)
void setColor (const Color &color)
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 ~GridCellsDisplay ()

Static Public Member Functions

static const char * getDescription ()
static const char * getTypeStatic ()

Protected Member Functions

void clear ()
void incomingMessage (const nav_msgs::GridCells::ConstPtr &msg)
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 processMessage (const nav_msgs::GridCells::ConstPtr &msg)
void subscribe ()
void unsubscribe ()

Protected Attributes

float alpha_
FloatPropertyWPtr alpha_property_
ogre_tools::PointCloudcloud_
Color color_
ColorPropertyWPtr color_property_
nav_msgs::GridCells::ConstPtr current_message_
uint32_t messages_received_
Ogre::SceneNode * scene_node_
message_filters::Subscriber
< nav_msgs::GridCells
sub_
tf::MessageFilter
< nav_msgs::GridCells
tf_filter_
std::string topic_
ROSTopicStringPropertyWPtr topic_property_

Detailed Description

Displays a nav_msgs::GridCells message.

Definition at line 64 of file grid_cells_display.h.


Constructor & Destructor Documentation

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

Definition at line 33 of file grid_cells_display.cpp.

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

Definition at line 57 of file grid_cells_display.cpp.


Member Function Documentation

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

Definition at line 66 of file grid_cells_display.cpp.

void rviz::GridCellsDisplay::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 237 of file grid_cells_display.cpp.

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

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

Implements rviz::Display.

Definition at line 137 of file grid_cells_display.cpp.

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

Definition at line 77 of file grid_cells_display.h.

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

Definition at line 74 of file grid_cells_display.h.

const char * rviz::GridCellsDisplay::getDescription (  )  [static]

Definition at line 253 of file grid_cells_display.cpp.

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

Definition at line 71 of file grid_cells_display.h.

virtual const char* rviz::GridCellsDisplay::getType (  )  const [inline, virtual]

Definition at line 87 of file grid_cells_display.h.

static const char* rviz::GridCellsDisplay::getTypeStatic (  )  [inline, static]

Definition at line 86 of file grid_cells_display.h.

void rviz::GridCellsDisplay::incomingMessage ( const nav_msgs::GridCells::ConstPtr msg  )  [protected]

Definition at line 226 of file grid_cells_display.cpp.

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

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

Implements rviz::Display.

Definition at line 130 of file grid_cells_display.cpp.

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

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

Implements rviz::Display.

Definition at line 124 of file grid_cells_display.cpp.

void rviz::GridCellsDisplay::processMessage ( const nav_msgs::GridCells::ConstPtr msg  )  [protected]

Definition at line 157 of file grid_cells_display.cpp.

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

Called to tell the display to clear its state.

Reimplemented from rviz::Display.

Definition at line 231 of file grid_cells_display.cpp.

void rviz::GridCellsDisplay::setAlpha ( float  alpha  ) 

Definition at line 97 of file grid_cells_display.cpp.

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

Definition at line 87 of file grid_cells_display.cpp.

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

Definition at line 74 of file grid_cells_display.cpp.

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

Definition at line 109 of file grid_cells_display.cpp.

virtual void rviz::GridCellsDisplay::targetFrameChanged (  )  [inline, virtual]

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

Implements rviz::Display.

Definition at line 80 of file grid_cells_display.h.

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

Definition at line 119 of file grid_cells_display.cpp.

void rviz::GridCellsDisplay::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 144 of file grid_cells_display.cpp.


Member Data Documentation

float rviz::GridCellsDisplay::alpha_ [protected]

Definition at line 103 of file grid_cells_display.h.

FloatPropertyWPtr rviz::GridCellsDisplay::alpha_property_ [protected]

Definition at line 114 of file grid_cells_display.h.

Definition at line 106 of file grid_cells_display.h.

Definition at line 102 of file grid_cells_display.h.

ColorPropertyWPtr rviz::GridCellsDisplay::color_property_ [protected]

Definition at line 112 of file grid_cells_display.h.

Definition at line 110 of file grid_cells_display.h.

Definition at line 116 of file grid_cells_display.h.

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

Definition at line 105 of file grid_cells_display.h.

Definition at line 108 of file grid_cells_display.h.

Definition at line 109 of file grid_cells_display.h.

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

Definition at line 101 of file grid_cells_display.h.

ROSTopicStringPropertyWPtr rviz::GridCellsDisplay::topic_property_ [protected]

Definition at line 113 of file grid_cells_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, Dave Hershberger
autogenerated on Sat Mar 2 14:17:35 2013