#include <but_cam_display.h>

| Public Member Functions | |
| CButCamDisplay (const std::string &name, VisualizationManager *manager) | |
| virtual void | createProperties () | 
| Overriden from Display. | |
| virtual void | fixedFrameChanged () | 
| Overriden from Display. | |
| float | getAlpha () | 
| alpha property getter | |
| float | getDistance () | 
| distance property getter | |
| bool | getDrawUnder () | 
| draw_under property getter | |
| float | getHeight () | 
| height property getter | |
| int | getImageHeight () | 
| image_height property getter | |
| const std::string & | getImageTopic () | 
| image_topic property getter | |
| int | getImageWidth () | 
| image_width property getter | |
| const std::string & | getMarkerTopic () | 
| marker_topic property getter | |
| Ogre::Quaternion | getOrientation () | 
| orientation property getter | |
| Ogre::Vector3 | getPosition () | 
| position property getter | |
| float | getWidth () | 
| width property getter | |
| virtual void | reset () | 
| Overriden from Display. | |
| void | setAlpha (float alpha) | 
| alpha property setter | |
| void | setDistance (float distance) | 
| distance property setter | |
| void | setDrawUnder (bool write) | 
| draw_under property setter | |
| void | setImageTopic (const std::string &topic) | 
| image_topic property setter | |
| void | setMarkerTopic (const std::string &topic) | 
| virtual void | targetFrameChanged () | 
| Overriden from Display. | |
| virtual void | update (float wall_dt, float ros_dt) | 
| Overriden from Display. | |
| virtual | ~CButCamDisplay () | 
| Protected Types | |
| typedef message_filters::sync_policies::ApproximateTime < srs_ui_but::ButCamMsg, sensor_msgs::Image > | App_sync_policy | 
| Protected Member Functions | |
| void | clear () | 
| Destroy created Ogre objects and textures. | |
| void | clearMarker () | 
| Destroy only created Ogre object manual_object_. | |
| void | imSubscribe () | 
| Subscribes to the "Image" topic. | |
| void | imUnsubscribe () | 
| Unsubscribes from the "Image" topic. | |
| void | incoming (const srs_ui_but::ButCamMsg::ConstPtr &msg, const sensor_msgs::Image::ConstPtr &image) | 
| callback function for both ButCamMsg and Image messages synchronized arrival | |
| void | incomingImage (const sensor_msgs::Image::ConstPtr &image) | 
| callback function for Image message arrival | |
| void | incomingMarker (const srs_ui_but::ButCamMsg::ConstPtr &msg) | 
| callback function for ButCamMsg message arrival | |
| void | load (const srs_ui_but::ButCamMsg::ConstPtr &msg) | 
| Creates and/or updates position of video frame polygon. | |
| void | loadImage (const sensor_msgs::Image::ConstPtr &image) | 
| Creates and/or updates texture of video frame polygon. | |
| virtual void | onDisable () | 
| Overriden from Display. | |
| virtual void | onEnable () | 
| Overriden from Display. | |
| virtual void | subscribe () | 
| Subscribes to the "visualization_marker" topic. | |
| void | synchronise () | 
| Starts and stops time synchronization of messages. | |
| void | transformCam () | 
| Makes sure the polygon position/orientation informations are related to correct frame. | |
| virtual void | unsubscribe () | 
| Unsubscribes from the "visualization_marker" topic. | |
| Protected Attributes | |
| float | alpha_ | 
| FloatPropertyWPtr | alpha_property_ | 
| float | distance_ | 
| FloatPropertyWPtr | distance_property_ | 
| bool | draw_under_ | 
| BoolPropertyWPtr | draw_under_property_ | 
| std::string | frame_ | 
| float | height_ | 
| FloatPropertyWPtr | height_property_ | 
| sensor_msgs::Image::ConstPtr | image_ | 
| int | image_height_ | 
| IntPropertyWPtr | image_height_property_ | 
| bool | image_loaded_ | 
| message_filters::Subscriber < sensor_msgs::Image > * | image_sub_ptr_ | 
| bool | image_subscribed_ | 
| std::string | image_topic_ | 
| ROSTopicStringPropertyWPtr | image_topic_property_ | 
| int | image_width_ | 
| IntPropertyWPtr | image_width_property_ | 
| Ogre::ManualObject * | manual_object_ | 
| srs_ui_but::ButCamMsg::ConstPtr | marker_ | 
| bool | marker_loaded_ | 
| message_filters::Subscriber < srs_ui_but::ButCamMsg > * | marker_sub_ptr_ | 
| bool | marker_subscribed_ | 
| std::string | marker_topic_ | 
| ROSTopicStringPropertyWPtr | marker_topic_property_ | 
| Ogre::MaterialPtr | material_ | 
| Ogre::Quaternion | orientation_ | 
| QuaternionPropertyWPtr | orientation_property_ | 
| Ogre::Vector3 | position_ | 
| Vector3PropertyWPtr | position_property_ | 
| Ogre::SceneNode * | scene_node_ | 
| Ogre::TexturePtr | texture_ | 
| message_filters::Synchronizer < App_sync_policy > * | time_sync_ptr_ | 
| bool | time_synced_ | 
| float | width_ | 
| FloatPropertyWPtr | width_property_ | 
Definition at line 65 of file but_cam_display.h.
| typedef message_filters::sync_policies::ApproximateTime< srs_ui_but::ButCamMsg, sensor_msgs::Image> rviz::CButCamDisplay::App_sync_policy  [protected] | 
Definition at line 347 of file but_cam_display.h.
| rviz::CButCamDisplay::CButCamDisplay | ( | const std::string & | name, | 
| VisualizationManager * | manager | ||
| ) | 
Constructor
Definition at line 54 of file but_cam_display.cpp.
| rviz::CButCamDisplay::~CButCamDisplay | ( | ) |  [virtual] | 
Destructor
Definition at line 89 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::clear | ( | void | ) |  [protected] | 
Destroy created Ogre objects and textures.
Definition at line 321 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::clearMarker | ( | ) |  [protected] | 
Destroy only created Ogre object manual_object_.
Definition at line 308 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::createProperties | ( | ) |  [virtual] | 
Overriden from Display.
Reimplemented from rviz::Display.
Definition at line 629 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::fixedFrameChanged | ( | ) |  [virtual] | 
Overriden from Display.
Reimplemented from rviz::Display.
Definition at line 737 of file but_cam_display.cpp.
| float rviz::CButCamDisplay::getAlpha | ( | ) |  [inline] | 
alpha property getter
Definition at line 150 of file but_cam_display.h.
| float rviz::CButCamDisplay::getDistance | ( | ) |  [inline] | 
distance property getter
Definition at line 164 of file but_cam_display.h.
| bool rviz::CButCamDisplay::getDrawUnder | ( | ) |  [inline] | 
draw_under property getter
Definition at line 178 of file but_cam_display.h.
| float rviz::CButCamDisplay::getHeight | ( | ) |  [inline] | 
height property getter
Definition at line 115 of file but_cam_display.h.
| int rviz::CButCamDisplay::getImageHeight | ( | ) |  [inline] | 
image_height property getter
Definition at line 129 of file but_cam_display.h.
| const std::string& rviz::CButCamDisplay::getImageTopic | ( | ) |  [inline] | 
image_topic property getter
Definition at line 87 of file but_cam_display.h.
| int rviz::CButCamDisplay::getImageWidth | ( | ) |  [inline] | 
image_width property getter
Definition at line 122 of file but_cam_display.h.
| const std::string& rviz::CButCamDisplay::getMarkerTopic | ( | ) |  [inline] | 
marker_topic property getter
Definition at line 101 of file but_cam_display.h.
| Ogre::Quaternion rviz::CButCamDisplay::getOrientation | ( | ) |  [inline] | 
orientation property getter
Definition at line 143 of file but_cam_display.h.
| Ogre::Vector3 rviz::CButCamDisplay::getPosition | ( | ) |  [inline] | 
position property getter
Definition at line 136 of file but_cam_display.h.
| float rviz::CButCamDisplay::getWidth | ( | ) |  [inline] | 
width property getter
Definition at line 108 of file but_cam_display.h.
| void rviz::CButCamDisplay::imSubscribe | ( | ) |  [protected] | 
Subscribes to the "Image" topic.
Definition at line 172 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::imUnsubscribe | ( | ) |  [protected] | 
Unsubscribes from the "Image" topic.
Definition at line 190 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::incoming | ( | const srs_ui_but::ButCamMsg::ConstPtr & | msg, | 
| const sensor_msgs::Image::ConstPtr & | image | ||
| ) |  [protected] | 
callback function for both ButCamMsg and Image messages synchronized arrival
| msg | newly arrived ButCamMsg message | 
| image | newly arrived camera image message | 
Definition at line 754 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::incomingImage | ( | const sensor_msgs::Image::ConstPtr & | image | ) |  [protected] | 
callback function for Image message arrival
| image | newly arrived camera image message | 
Definition at line 774 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::incomingMarker | ( | const srs_ui_but::ButCamMsg::ConstPtr & | msg | ) |  [protected] | 
callback function for ButCamMsg message arrival
| msg | newly arrived ButCamMsg message | 
Definition at line 767 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::load | ( | const srs_ui_but::ButCamMsg::ConstPtr & | msg | ) |  [protected] | 
Creates and/or updates position of video frame polygon.
| msg | obtained ButCamMsg message | 
Definition at line 482 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::loadImage | ( | const sensor_msgs::Image::ConstPtr & | image | ) |  [protected] | 
Creates and/or updates texture of video frame polygon.
| image | obtained camera image message | 
Definition at line 347 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::onDisable | ( | ) |  [protected, virtual] | 
Overriden from Display.
Implements rviz::Display.
Definition at line 108 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::onEnable | ( | ) |  [protected, virtual] | 
Overriden from Display.
Implements rviz::Display.
Definition at line 98 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::reset | ( | ) |  [virtual] | 
Overriden from Display.
Reimplemented from rviz::Display.
Definition at line 742 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::setAlpha | ( | float | alpha | ) | 
alpha property setter
| alpha | new alpha | 
Definition at line 213 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::setDistance | ( | float | distance | ) | 
distance property setter
| distance | new ploygon rendering distance | 
Definition at line 199 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::setDrawUnder | ( | bool | write | ) | 
draw_under property setter
| write | true for drawing under, false for not | 
Definition at line 249 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::setImageTopic | ( | const std::string & | topic | ) | 
image_topic property setter
| topic | new image topic | 
Definition at line 288 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::setMarkerTopic | ( | const std::string & | topic | ) | 
marker_topic property setter
| topic | new ButCamMsg topic | 
Definition at line 271 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::subscribe | ( | ) |  [protected, virtual] | 
Subscribes to the "visualization_marker" topic.
Definition at line 144 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::synchronise | ( | ) |  [protected] | 
Starts and stops time synchronization of messages.
Definition at line 119 of file but_cam_display.cpp.
| virtual void rviz::CButCamDisplay::targetFrameChanged | ( | ) |  [inline, virtual] | 
Overriden from Display.
Definition at line 192 of file but_cam_display.h.
| void rviz::CButCamDisplay::transformCam | ( | ) |  [protected] | 
Makes sure the polygon position/orientation informations are related to correct frame.
Definition at line 595 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::unsubscribe | ( | ) |  [protected, virtual] | 
Unsubscribes from the "visualization_marker" topic.
Definition at line 163 of file but_cam_display.cpp.
| void rviz::CButCamDisplay::update | ( | float | wall_dt, | 
| float | ros_dt | ||
| ) |  [virtual] | 
Overriden from Display.
Reimplemented from rviz::Display.
Definition at line 625 of file but_cam_display.cpp.
| float rviz::CButCamDisplay::alpha_  [protected] | 
Definition at line 382 of file but_cam_display.h.
| FloatPropertyWPtr rviz::CButCamDisplay::alpha_property_  [protected] | 
Definition at line 383 of file but_cam_display.h.
| float rviz::CButCamDisplay::distance_  [protected] | 
Definition at line 370 of file but_cam_display.h.
| FloatPropertyWPtr rviz::CButCamDisplay::distance_property_  [protected] | 
Definition at line 371 of file but_cam_display.h.
| bool rviz::CButCamDisplay::draw_under_  [protected] | 
Definition at line 386 of file but_cam_display.h.
| BoolPropertyWPtr rviz::CButCamDisplay::draw_under_property_  [protected] | 
Definition at line 387 of file but_cam_display.h.
| std::string rviz::CButCamDisplay::frame_  [protected] | 
Definition at line 331 of file but_cam_display.h.
| float rviz::CButCamDisplay::height_  [protected] | 
Definition at line 366 of file but_cam_display.h.
| FloatPropertyWPtr rviz::CButCamDisplay::height_property_  [protected] | 
Definition at line 367 of file but_cam_display.h.
| sensor_msgs::Image::ConstPtr rviz::CButCamDisplay::image_  [protected] | 
Definition at line 334 of file but_cam_display.h.
| int rviz::CButCamDisplay::image_height_  [protected] | 
Definition at line 358 of file but_cam_display.h.
| IntPropertyWPtr rviz::CButCamDisplay::image_height_property_  [protected] | 
Definition at line 359 of file but_cam_display.h.
| bool rviz::CButCamDisplay::image_loaded_  [protected] | 
Definition at line 320 of file but_cam_display.h.
| message_filters::Subscriber<sensor_msgs::Image>* rviz::CButCamDisplay::image_sub_ptr_  [protected] | 
Definition at line 342 of file but_cam_display.h.
| bool rviz::CButCamDisplay::image_subscribed_  [protected] | 
Definition at line 343 of file but_cam_display.h.
| std::string rviz::CButCamDisplay::image_topic_  [protected] | 
Definition at line 327 of file but_cam_display.h.
| ROSTopicStringPropertyWPtr rviz::CButCamDisplay::image_topic_property_  [protected] | 
Definition at line 328 of file but_cam_display.h.
| int rviz::CButCamDisplay::image_width_  [protected] | 
Definition at line 354 of file but_cam_display.h.
| IntPropertyWPtr rviz::CButCamDisplay::image_width_property_  [protected] | 
Definition at line 355 of file but_cam_display.h.
| Ogre::ManualObject* rviz::CButCamDisplay::manual_object_  [protected] | 
Definition at line 308 of file but_cam_display.h.
| srs_ui_but::ButCamMsg::ConstPtr rviz::CButCamDisplay::marker_  [protected] | 
Definition at line 337 of file but_cam_display.h.
| bool rviz::CButCamDisplay::marker_loaded_  [protected] | 
Definition at line 317 of file but_cam_display.h.
| message_filters::Subscriber<srs_ui_but::ButCamMsg>* rviz::CButCamDisplay::marker_sub_ptr_  [protected] | 
Definition at line 340 of file but_cam_display.h.
| bool rviz::CButCamDisplay::marker_subscribed_  [protected] | 
Definition at line 341 of file but_cam_display.h.
| std::string rviz::CButCamDisplay::marker_topic_  [protected] | 
Definition at line 323 of file but_cam_display.h.
| ROSTopicStringPropertyWPtr rviz::CButCamDisplay::marker_topic_property_  [protected] | 
Definition at line 324 of file but_cam_display.h.
| Ogre::MaterialPtr rviz::CButCamDisplay::material_  [protected] | 
Definition at line 314 of file but_cam_display.h.
| Ogre::Quaternion rviz::CButCamDisplay::orientation_  [protected] | 
Definition at line 378 of file but_cam_display.h.
| QuaternionPropertyWPtr rviz::CButCamDisplay::orientation_property_  [protected] | 
Definition at line 379 of file but_cam_display.h.
| Ogre::Vector3 rviz::CButCamDisplay::position_  [protected] | 
Definition at line 374 of file but_cam_display.h.
| Vector3PropertyWPtr rviz::CButCamDisplay::position_property_  [protected] | 
Definition at line 375 of file but_cam_display.h.
| Ogre::SceneNode* rviz::CButCamDisplay::scene_node_  [protected] | 
Definition at line 305 of file but_cam_display.h.
| Ogre::TexturePtr rviz::CButCamDisplay::texture_  [protected] | 
Definition at line 311 of file but_cam_display.h.
Definition at line 350 of file but_cam_display.h.
| bool rviz::CButCamDisplay::time_synced_  [protected] | 
Definition at line 351 of file but_cam_display.h.
| float rviz::CButCamDisplay::width_  [protected] | 
Definition at line 362 of file but_cam_display.h.
| FloatPropertyWPtr rviz::CButCamDisplay::width_property_  [protected] | 
Definition at line 363 of file but_cam_display.h.