#include <image_display.h>
Public Slots | |
virtual void | updateNormalizeOptions () |
Public Member Functions | |
ImageDisplay () | |
virtual void | onInitialize () |
Override this function to do subclass-specific initialization. | |
virtual void | reset () |
Reset display. | |
virtual void | update (float wall_dt, float ros_dt) |
Called periodically by the visualization manager. | |
virtual | ~ImageDisplay () |
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. | |
virtual void | processMessage (const sensor_msgs::Image::ConstPtr &msg) |
Implement this to process the contents of a message. | |
Private Member Functions | |
void | clear () |
void | updateStatus () |
Private Attributes | |
bool | got_float_image_ |
Ogre::SceneManager * | img_scene_manager_ |
Ogre::SceneNode * | img_scene_node_ |
Ogre::MaterialPtr | material_ |
FloatProperty * | max_property_ |
IntProperty * | median_buffer_size_property_ |
FloatProperty * | min_property_ |
BoolProperty * | normalize_property_ |
RenderPanel * | render_panel_ |
Ogre::Rectangle2D * | screen_rect_ |
ROSImageTexture | texture_ |
Definition at line 63 of file image_display.h.
Definition at line 59 of file image_display.cpp.
rviz::ImageDisplay::~ImageDisplay | ( | ) | [virtual] |
Definition at line 134 of file image_display.cpp.
void rviz::ImageDisplay::clear | ( | ) | [private] |
Definition at line 180 of file image_display.cpp.
void rviz::ImageDisplay::onDisable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of disabling themselves.
Reimplemented from rviz::Display.
Definition at line 150 of file image_display.cpp.
void rviz::ImageDisplay::onEnable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of enabling themselves.
Reimplemented from rviz::Display.
Definition at line 144 of file image_display.cpp.
void rviz::ImageDisplay::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::ImageDisplayBase.
Definition at line 77 of file image_display.cpp.
void rviz::ImageDisplay::processMessage | ( | const sensor_msgs::Image::ConstPtr & | msg | ) | [protected, virtual] |
Implement this to process the contents of a message.
This is called by incomingMessage().
Implements rviz::ImageDisplayBase.
Definition at line 233 of file image_display.cpp.
void rviz::ImageDisplay::reset | ( | ) | [virtual] |
Reset display.
Reimplemented from rviz::ImageDisplayBase.
Definition at line 226 of file image_display.cpp.
void rviz::ImageDisplay::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 190 of file image_display.cpp.
void rviz::ImageDisplay::updateNormalizeOptions | ( | ) | [virtual, slot] |
Definition at line 157 of file image_display.cpp.
void rviz::ImageDisplay::updateStatus | ( | ) | [private] |
bool rviz::ImageDisplay::got_float_image_ [private] |
Definition at line 103 of file image_display.h.
Ogre::SceneManager* rviz::ImageDisplay::img_scene_manager_ [private] |
Definition at line 90 of file image_display.h.
Ogre::SceneNode* rviz::ImageDisplay::img_scene_node_ [private] |
Definition at line 91 of file image_display.h.
Ogre::MaterialPtr rviz::ImageDisplay::material_ [private] |
Definition at line 93 of file image_display.h.
FloatProperty* rviz::ImageDisplay::max_property_ [private] |
Definition at line 101 of file image_display.h.
Definition at line 102 of file image_display.h.
FloatProperty* rviz::ImageDisplay::min_property_ [private] |
Definition at line 100 of file image_display.h.
Definition at line 99 of file image_display.h.
RenderPanel* rviz::ImageDisplay::render_panel_ [private] |
Definition at line 97 of file image_display.h.
Ogre::Rectangle2D* rviz::ImageDisplay::screen_rect_ [private] |
Definition at line 92 of file image_display.h.
ROSImageTexture rviz::ImageDisplay::texture_ [private] |
Definition at line 95 of file image_display.h.