Displays a nav_msgs::GridCells message. More...
#include <grid_cells_display.h>
Public Member Functions | |
virtual void | createProperties () |
Called from setPropertyManager, gives the display a chance to create some properties immediately. | |
virtual void | fixedFrameChanged () |
Override to handle changes to fixed_frame_. This base class implementation does nothing. | |
float | getAlpha () |
const Color & | getColor () |
const std::string & | getTopic () |
virtual const char * | getType () const |
GridCellsDisplay () | |
virtual void | hideVisible () |
Hides all visible parts of this display, so they do not show up when the scene is rendered. | |
virtual void | onInitialize () |
Override this function to do subclass-specific initialization. | |
virtual void | reset () |
Called to tell the display to clear its state. | |
virtual void | restoreVisible () |
Restores the display to the state it was in before hideVisible() was called. | |
void | setAlpha (float alpha) |
void | setColor (const Color &color) |
void | setTopic (const std::string &topic) |
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_ |
PointCloud * | cloud_ |
Color | color_ |
ColorPropertyWPtr | color_property_ |
nav_msgs::GridCells::ConstPtr | current_message_ |
bool | hidden_ |
uint64_t | last_frame_count_ |
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_ |
Displays a nav_msgs::GridCells message.
Definition at line 64 of file grid_cells_display.h.
Definition at line 53 of file grid_cells_display.cpp.
rviz::GridCellsDisplay::~GridCellsDisplay | ( | ) | [virtual] |
Definition at line 83 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::clear | ( | void | ) | [protected] |
Definition at line 93 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::createProperties | ( | ) | [virtual] |
Called from setPropertyManager, gives the display a chance to create some properties immediately.
When this function is called, the property_manager_ member is valid and will stay valid
Reimplemented from rviz::Display.
Definition at line 291 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::fixedFrameChanged | ( | ) | [virtual] |
Override to handle changes to fixed_frame_. This base class implementation does nothing.
Reimplemented from rviz::Display.
Definition at line 185 of file grid_cells_display.cpp.
float rviz::GridCellsDisplay::getAlpha | ( | ) | [inline] |
Definition at line 79 of file grid_cells_display.h.
const Color& rviz::GridCellsDisplay::getColor | ( | ) | [inline] |
Definition at line 76 of file grid_cells_display.h.
const char * rviz::GridCellsDisplay::getDescription | ( | ) | [static] |
Definition at line 307 of file grid_cells_display.cpp.
const std::string& rviz::GridCellsDisplay::getTopic | ( | ) | [inline] |
Definition at line 73 of file grid_cells_display.h.
virtual const char* rviz::GridCellsDisplay::getType | ( | ) | const [inline, virtual] |
Definition at line 88 of file grid_cells_display.h.
static const char* rviz::GridCellsDisplay::getTypeStatic | ( | ) | [inline, static] |
Definition at line 87 of file grid_cells_display.h.
void rviz::GridCellsDisplay::hideVisible | ( | ) | [virtual] |
Hides all visible parts of this display, so they do not show up when the scene is rendered.
Reimplemented from rviz::Display.
Definition at line 173 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::incomingMessage | ( | const nav_msgs::GridCells::ConstPtr & | msg | ) | [protected] |
Definition at line 280 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 166 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 160 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::onInitialize | ( | ) | [virtual] |
Override this function to do subclass-specific initialization.
This is called after vis_manager_ and scene_manager_ are set.
Reimplemented from rviz::Display.
Definition at line 62 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::processMessage | ( | const nav_msgs::GridCells::ConstPtr & | msg | ) | [protected] |
Definition at line 205 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 285 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::restoreVisible | ( | ) | [virtual] |
Restores the display to the state it was in before hideVisible() was called.
Reimplemented from rviz::Display.
Definition at line 179 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::setAlpha | ( | float | alpha | ) |
Definition at line 124 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::setColor | ( | const Color & | color | ) |
Definition at line 114 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::setTopic | ( | const std::string & | topic | ) |
Definition at line 101 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::subscribe | ( | ) | [protected] |
Definition at line 136 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::unsubscribe | ( | ) | [protected] |
Definition at line 154 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::update | ( | float | wall_dt, |
float | ros_dt | ||
) | [virtual] |
Called periodically by the visualization panel.
dt | Wall-clock time, in seconds, since the last time the update list was run through. |
Reimplemented from rviz::Display.
Definition at line 192 of file grid_cells_display.cpp.
float rviz::GridCellsDisplay::alpha_ [protected] |
Definition at line 110 of file grid_cells_display.h.
FloatPropertyWPtr rviz::GridCellsDisplay::alpha_property_ [protected] |
Definition at line 121 of file grid_cells_display.h.
PointCloud* rviz::GridCellsDisplay::cloud_ [protected] |
Definition at line 113 of file grid_cells_display.h.
Color rviz::GridCellsDisplay::color_ [protected] |
Definition at line 109 of file grid_cells_display.h.
ColorPropertyWPtr rviz::GridCellsDisplay::color_property_ [protected] |
Definition at line 119 of file grid_cells_display.h.
nav_msgs::GridCells::ConstPtr rviz::GridCellsDisplay::current_message_ [protected] |
Definition at line 117 of file grid_cells_display.h.
bool rviz::GridCellsDisplay::hidden_ [protected] |
Definition at line 126 of file grid_cells_display.h.
uint64_t rviz::GridCellsDisplay::last_frame_count_ [protected] |
Definition at line 124 of file grid_cells_display.h.
uint32_t rviz::GridCellsDisplay::messages_received_ [protected] |
Definition at line 123 of file grid_cells_display.h.
Ogre::SceneNode* rviz::GridCellsDisplay::scene_node_ [protected] |
Definition at line 112 of file grid_cells_display.h.
message_filters::Subscriber<nav_msgs::GridCells> rviz::GridCellsDisplay::sub_ [protected] |
Definition at line 115 of file grid_cells_display.h.
tf::MessageFilter<nav_msgs::GridCells>* rviz::GridCellsDisplay::tf_filter_ [protected] |
Definition at line 116 of file grid_cells_display.h.
std::string rviz::GridCellsDisplay::topic_ [protected] |
Definition at line 108 of file grid_cells_display.h.
ROSTopicStringPropertyWPtr rviz::GridCellsDisplay::topic_property_ [protected] |
Definition at line 120 of file grid_cells_display.h.