$search
#include <camera_display.h>
Classes | |
class | RenderListener |
Public Member Functions | |
CameraDisplay (const std::string &name, VisualizationManager *manager) | |
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 std::string & | getImagePosition () |
const std::string & | getTopic () |
const std::string & | getTransport () |
float | getZoom () |
virtual void | reset () |
Called to tell the display to clear its state. | |
void | setAlpha (float alpha) |
void | setImagePosition (const std::string &image_position) |
void | setTopic (const std::string &topic) |
void | setTransport (const std::string &transport) |
void | setZoom (float zoom) |
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 | ~CameraDisplay () |
Protected Member Functions | |
void | caminfoCallback (const sensor_msgs::CameraInfo::ConstPtr &msg) |
void | clear () |
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 | onImagePositionEnumOptions (V_string &choices) |
void | onTransportEnumOptions (V_string &choices) |
void | subscribe () |
void | unsubscribe () |
void | updateCamera () |
void | updateStatus () |
Protected Attributes | |
float | alpha_ |
FloatPropertyWPtr | alpha_property_ |
Ogre::MaterialPtr | bg_material_ |
Ogre::SceneNode * | bg_scene_node_ |
Ogre::Rectangle2D * | bg_screen_rect_ |
boost::mutex | caminfo_mutex_ |
message_filters::Subscriber < sensor_msgs::CameraInfo > | caminfo_sub_ |
tf::MessageFilter < sensor_msgs::CameraInfo > | caminfo_tf_filter_ |
sensor_msgs::CameraInfo::ConstPtr | current_caminfo_ |
Ogre::MaterialPtr | fg_material_ |
Ogre::SceneNode * | fg_scene_node_ |
Ogre::Rectangle2D * | fg_screen_rect_ |
bool | force_render_ |
wxFrame * | frame_ |
std::string | image_position_ |
EditEnumPropertyWPtr | image_position_property_ |
bool | new_caminfo_ |
RenderListener | render_listener_ |
RenderPanel * | render_panel_ |
ROSImageTexture | texture_ |
std::string | topic_ |
ROSTopicStringPropertyWPtr | topic_property_ |
std::string | transport_ |
EditEnumPropertyWPtr | transport_property_ |
float | zoom_ |
FloatPropertyWPtr | zoom_property_ |
Definition at line 64 of file camera_display.h.
rviz::CameraDisplay::CameraDisplay | ( | const std::string & | name, | |
VisualizationManager * | manager | |||
) |
Definition at line 65 of file camera_display.cpp.
rviz::CameraDisplay::~CameraDisplay | ( | ) | [virtual] |
Definition at line 171 of file camera_display.cpp.
void rviz::CameraDisplay::caminfoCallback | ( | const sensor_msgs::CameraInfo::ConstPtr & | msg | ) | [protected] |
Definition at line 518 of file camera_display.cpp.
void rviz::CameraDisplay::clear | ( | ) | [protected] |
Definition at line 326 of file camera_display.cpp.
void rviz::CameraDisplay::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 538 of file camera_display.cpp.
void rviz::CameraDisplay::fixedFrameChanged | ( | ) | [virtual] |
Called from within setFixedFrame, notifying child classes that the fixed frame has changed.
Implements rviz::Display.
Definition at line 566 of file camera_display.cpp.
float rviz::CameraDisplay::getAlpha | ( | ) | [inline] |
Definition at line 70 of file camera_display.h.
const std::string& rviz::CameraDisplay::getImagePosition | ( | ) | [inline] |
Definition at line 79 of file camera_display.h.
const std::string& rviz::CameraDisplay::getTopic | ( | ) | [inline] |
Definition at line 73 of file camera_display.h.
const std::string& rviz::CameraDisplay::getTransport | ( | ) | [inline] |
Definition at line 76 of file camera_display.h.
float rviz::CameraDisplay::getZoom | ( | ) | [inline] |
Definition at line 82 of file camera_display.h.
void rviz::CameraDisplay::onDisable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of disabling themselves.
Implements rviz::Display.
Definition at line 212 of file camera_display.cpp.
void rviz::CameraDisplay::onEnable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of enabling themselves.
Implements rviz::Display.
Definition at line 194 of file camera_display.cpp.
void rviz::CameraDisplay::onImagePositionEnumOptions | ( | V_string & | choices | ) | [protected] |
Definition at line 530 of file camera_display.cpp.
void rviz::CameraDisplay::onTransportEnumOptions | ( | V_string & | choices | ) | [protected] |
Definition at line 525 of file camera_display.cpp.
void rviz::CameraDisplay::reset | ( | ) | [virtual] |
Called to tell the display to clear its state.
Reimplemented from rviz::Display.
Definition at line 577 of file camera_display.cpp.
void rviz::CameraDisplay::setAlpha | ( | float | alpha | ) |
Definition at line 260 of file camera_display.cpp.
void rviz::CameraDisplay::setImagePosition | ( | const std::string & | image_position | ) |
Definition at line 316 of file camera_display.cpp.
void rviz::CameraDisplay::setTopic | ( | const std::string & | topic | ) |
Definition at line 295 of file camera_display.cpp.
void rviz::CameraDisplay::setTransport | ( | const std::string & | transport | ) |
Definition at line 307 of file camera_display.cpp.
void rviz::CameraDisplay::setZoom | ( | float | zoom | ) |
Definition at line 281 of file camera_display.cpp.
void rviz::CameraDisplay::subscribe | ( | ) | [protected] |
Definition at line 231 of file camera_display.cpp.
void rviz::CameraDisplay::targetFrameChanged | ( | ) | [virtual] |
Called from within setTargetFrame, notifying child classes that the target frame has changed.
Implements rviz::Display.
Definition at line 572 of file camera_display.cpp.
void rviz::CameraDisplay::unsubscribe | ( | ) | [protected] |
Definition at line 254 of file camera_display.cpp.
void rviz::CameraDisplay::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 355 of file camera_display.cpp.
void rviz::CameraDisplay::updateCamera | ( | ) | [protected] |
Definition at line 382 of file camera_display.cpp.
void rviz::CameraDisplay::updateStatus | ( | ) | [protected] |
Definition at line 341 of file camera_display.cpp.
float rviz::CameraDisplay::alpha_ [protected] |
Definition at line 120 of file camera_display.h.
FloatPropertyWPtr rviz::CameraDisplay::alpha_property_ [protected] |
Definition at line 129 of file camera_display.h.
Ogre::MaterialPtr rviz::CameraDisplay::bg_material_ [protected] |
Definition at line 115 of file camera_display.h.
Ogre::SceneNode* rviz::CameraDisplay::bg_scene_node_ [protected] |
Definition at line 111 of file camera_display.h.
Ogre::Rectangle2D* rviz::CameraDisplay::bg_screen_rect_ [protected] |
Definition at line 114 of file camera_display.h.
boost::mutex rviz::CameraDisplay::caminfo_mutex_ [protected] |
Definition at line 136 of file camera_display.h.
Definition at line 126 of file camera_display.h.
Definition at line 127 of file camera_display.h.
Definition at line 135 of file camera_display.h.
Ogre::MaterialPtr rviz::CameraDisplay::fg_material_ [protected] |
Definition at line 118 of file camera_display.h.
Ogre::SceneNode* rviz::CameraDisplay::fg_scene_node_ [protected] |
Definition at line 112 of file camera_display.h.
Ogre::Rectangle2D* rviz::CameraDisplay::fg_screen_rect_ [protected] |
Definition at line 117 of file camera_display.h.
bool rviz::CameraDisplay::force_render_ [protected] |
Definition at line 145 of file camera_display.h.
wxFrame* rviz::CameraDisplay::frame_ [protected] |
Definition at line 143 of file camera_display.h.
std::string rviz::CameraDisplay::image_position_ [protected] |
Definition at line 124 of file camera_display.h.
EditEnumPropertyWPtr rviz::CameraDisplay::image_position_property_ [protected] |
Definition at line 132 of file camera_display.h.
bool rviz::CameraDisplay::new_caminfo_ [protected] |
Definition at line 138 of file camera_display.h.
RenderListener rviz::CameraDisplay::render_listener_ [protected] |
Definition at line 157 of file camera_display.h.
RenderPanel* rviz::CameraDisplay::render_panel_ [protected] |
Definition at line 142 of file camera_display.h.
ROSImageTexture rviz::CameraDisplay::texture_ [protected] |
Definition at line 140 of file camera_display.h.
std::string rviz::CameraDisplay::topic_ [protected] |
Definition at line 122 of file camera_display.h.
ROSTopicStringPropertyWPtr rviz::CameraDisplay::topic_property_ [protected] |
Definition at line 130 of file camera_display.h.
std::string rviz::CameraDisplay::transport_ [protected] |
Definition at line 123 of file camera_display.h.
EditEnumPropertyWPtr rviz::CameraDisplay::transport_property_ [protected] |
Definition at line 131 of file camera_display.h.
float rviz::CameraDisplay::zoom_ [protected] |
Definition at line 121 of file camera_display.h.
FloatPropertyWPtr rviz::CameraDisplay::zoom_property_ [protected] |
Definition at line 133 of file camera_display.h.