Displays a Temperature message of type sensor_msgs::Temperature. More...
#include <temperature_display.h>

| Public Member Functions | |
| virtual void | reset () | 
| Called to tell the display to clear its state. | |
| TemperatureDisplay () | |
| virtual void | update (float wall_dt, float ros_dt) | 
| Called periodically by the visualization manager. | |
| ~TemperatureDisplay () | |
| Protected Member Functions | |
| virtual void | onInitialize () | 
| Do initialization. Overridden from MessageFilterDisplay. | |
| virtual void | processMessage (const sensor_msgs::TemperatureConstPtr &msg) | 
| Process a single message. Overridden from MessageFilterDisplay. | |
| Protected Attributes | |
| PointCloudCommon * | point_cloud_common_ | 
| IntProperty * | queue_size_property_ | 
| Private Slots | |
| void | updateQueueSize () | 
Displays a Temperature message of type sensor_msgs::Temperature.
Definition at line 49 of file temperature_display.h.
Definition at line 48 of file temperature_display.cpp.
Definition at line 62 of file temperature_display.cpp.
| void rviz::TemperatureDisplay::onInitialize | ( | ) |  [protected, virtual] | 
Do initialization. Overridden from MessageFilterDisplay.
Reimplemented from rviz::MessageFilterDisplay< sensor_msgs::Temperature >.
Definition at line 67 of file temperature_display.cpp.
| void rviz::TemperatureDisplay::processMessage | ( | const sensor_msgs::TemperatureConstPtr & | msg | ) |  [protected, virtual] | 
Process a single message. Overridden from MessageFilterDisplay.
Definition at line 85 of file temperature_display.cpp.
| void rviz::TemperatureDisplay::reset | ( | ) |  [virtual] | 
Called to tell the display to clear its state.
Reimplemented from rviz::MessageFilterDisplay< sensor_msgs::Temperature >.
Definition at line 146 of file temperature_display.cpp.
| void rviz::TemperatureDisplay::update | ( | float | wall_dt, | 
| float | ros_dt | ||
| ) |  [virtual] | 
Called periodically by the visualization manager.
| wall_dt | Wall-clock time, in seconds, since the last time the update list was run through. | 
| ros_dt | ROS time, in seconds, since the last time the update list was run through. | 
Reimplemented from rviz::Display.
Definition at line 134 of file temperature_display.cpp.
| void rviz::TemperatureDisplay::updateQueueSize | ( | ) |  [private, slot] | 
Definition at line 80 of file temperature_display.cpp.
Definition at line 72 of file temperature_display.h.
Definition at line 70 of file temperature_display.h.