Displays a nav_msgs::GridCells message. More...
#include <grid_cells_display.h>
Public Member Functions | |
virtual void | fixedFrameChanged () |
Called by setFixedFrame(). Override to respond to changes to fixed_frame_. | |
GridCellsDisplay () | |
virtual void | onInitialize () |
Override this function to do subclass-specific initialization. | |
virtual void | reset () |
Called to tell the display to clear its state. | |
virtual | ~GridCellsDisplay () |
Protected Member Functions | |
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. | |
Private Slots | |
void | updateAlpha () |
void | updateTopic () |
Private Member Functions | |
void | clear () |
void | incomingMessage (const nav_msgs::GridCells::ConstPtr &msg) |
void | subscribe () |
void | unsubscribe () |
Private Attributes | |
FloatProperty * | alpha_property_ |
PointCloud * | cloud_ |
ColorProperty * | color_property_ |
uint64_t | last_frame_count_ |
uint32_t | messages_received_ |
message_filters::Subscriber < nav_msgs::GridCells > | sub_ |
tf::MessageFilter < nav_msgs::GridCells > * | tf_filter_ |
RosTopicProperty * | topic_property_ |
Displays a nav_msgs::GridCells message.
Definition at line 63 of file grid_cells_display.h.
Definition at line 54 of file grid_cells_display.cpp.
rviz::GridCellsDisplay::~GridCellsDisplay | ( | ) | [virtual] |
Definition at line 94 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::clear | ( | ) | [private] |
Definition at line 106 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::fixedFrameChanged | ( | ) | [virtual] |
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
Reimplemented from rviz::Display.
Definition at line 161 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::incomingMessage | ( | const nav_msgs::GridCells::ConstPtr & | msg | ) | [private] |
Definition at line 177 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::onDisable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of disabling themselves.
Reimplemented from rviz::Display.
Definition at line 155 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::onEnable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of enabling themselves.
Reimplemented from rviz::Display.
Definition at line 150 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, and before load() or setEnabled().
setName() may or may not have been called before this.
Reimplemented from rviz::Display.
Definition at line 74 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 247 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::subscribe | ( | ) | [private] |
Definition at line 127 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::unsubscribe | ( | ) | [private] |
Definition at line 145 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::updateAlpha | ( | ) | [private, slot] |
Definition at line 121 of file grid_cells_display.cpp.
void rviz::GridCellsDisplay::updateTopic | ( | ) | [private, slot] |
Definition at line 114 of file grid_cells_display.cpp.
Definition at line 98 of file grid_cells_display.h.
PointCloud* rviz::GridCellsDisplay::cloud_ [private] |
Definition at line 91 of file grid_cells_display.h.
Definition at line 96 of file grid_cells_display.h.
uint64_t rviz::GridCellsDisplay::last_frame_count_ [private] |
Definition at line 101 of file grid_cells_display.h.
uint32_t rviz::GridCellsDisplay::messages_received_ [private] |
Definition at line 100 of file grid_cells_display.h.
message_filters::Subscriber<nav_msgs::GridCells> rviz::GridCellsDisplay::sub_ [private] |
Definition at line 93 of file grid_cells_display.h.
tf::MessageFilter<nav_msgs::GridCells>* rviz::GridCellsDisplay::tf_filter_ [private] |
Definition at line 94 of file grid_cells_display.h.
Definition at line 97 of file grid_cells_display.h.