Displays a map along the XY plane. More...
#include <map_display.h>

Public Member Functions | |
| virtual void | fixedFrameChanged () |
| Called by setFixedFrame(). Override to respond to changes to fixed_frame_. | |
| int | getHeight () |
| Ogre::Quaternion | getOrientation () |
| Ogre::Vector3 | getPosition () |
| float | getResolution () |
| int | getWidth () |
| MapDisplay () | |
| virtual void | onInitialize () |
| Override this function to do subclass-specific initialization. | |
| virtual void | reset () |
| Called to tell the display to clear its state. | |
| virtual void | update (float wall_dt, float ros_dt) |
| Called periodically by the visualization manager. | |
| virtual | ~MapDisplay () |
Protected Slots | |
| void | updateAlpha () |
| void | updateDrawUnder () |
| void | updateTopic () |
Protected Member Functions | |
| void | clear () |
| void | incomingMap (const nav_msgs::OccupancyGrid::ConstPtr &msg) |
| 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 | subscribe () |
| void | transformMap () |
| virtual void | unsubscribe () |
Protected Attributes | |
| FloatProperty * | alpha_property_ |
| nav_msgs::OccupancyGrid::ConstPtr | current_map_ |
| Property * | draw_under_property_ |
| std::string | frame_ |
| int | height_ |
| IntProperty * | height_property_ |
| bool | loaded_ |
| Ogre::ManualObject * | manual_object_ |
| ros::Subscriber | map_sub_ |
| Ogre::MaterialPtr | material_ |
| boost::mutex | mutex_ |
| bool | new_map_ |
| Ogre::Quaternion | orientation_ |
| QuaternionProperty * | orientation_property_ |
| Ogre::Vector3 | position_ |
| VectorProperty * | position_property_ |
| float | resolution_ |
| FloatProperty * | resolution_property_ |
| Ogre::TexturePtr | texture_ |
| std::string | topic_ |
| RosTopicProperty * | topic_property_ |
| nav_msgs::OccupancyGrid::ConstPtr | updated_map_ |
| int | width_ |
| IntProperty * | width_property_ |
Displays a map along the XY plane.
Definition at line 65 of file map_display.h.
Definition at line 58 of file map_display.cpp.
| rviz::MapDisplay::~MapDisplay | ( | ) | [virtual] |
Definition at line 109 of file map_display.cpp.
| void rviz::MapDisplay::clear | ( | ) | [protected] |
Definition at line 226 of file map_display.cpp.
| void rviz::MapDisplay::fixedFrameChanged | ( | ) | [virtual] |
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
Reimplemented from rviz::Display.
Definition at line 519 of file map_display.cpp.
| int rviz::MapDisplay::getHeight | ( | ) | [inline] |
Definition at line 80 of file map_display.h.
| Ogre::Quaternion rviz::MapDisplay::getOrientation | ( | ) | [inline] |
Definition at line 82 of file map_display.h.
| Ogre::Vector3 rviz::MapDisplay::getPosition | ( | ) | [inline] |
Definition at line 81 of file map_display.h.
| float rviz::MapDisplay::getResolution | ( | ) | [inline] |
Definition at line 78 of file map_display.h.
| int rviz::MapDisplay::getWidth | ( | ) | [inline] |
Definition at line 79 of file map_display.h.
| void rviz::MapDisplay::incomingMap | ( | const nav_msgs::OccupancyGrid::ConstPtr & | msg | ) | [protected] |
Definition at line 483 of file map_display.cpp.
| void rviz::MapDisplay::onDisable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of disabling themselves.
Reimplemented from rviz::Display.
Definition at line 136 of file map_display.cpp.
| void rviz::MapDisplay::onEnable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of enabling themselves.
Reimplemented from rviz::Display.
Definition at line 131 of file map_display.cpp.
| void rviz::MapDisplay::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 115 of file map_display.cpp.
| void rviz::MapDisplay::reset | ( | ) | [virtual] |
Called to tell the display to clear its state.
Reimplemented from rviz::Display.
Definition at line 524 of file map_display.cpp.
| void rviz::MapDisplay::subscribe | ( | ) | [protected, virtual] |
Definition at line 142 of file map_display.cpp.
| void rviz::MapDisplay::transformMap | ( | ) | [protected] |
Definition at line 493 of file map_display.cpp.
| void rviz::MapDisplay::unsubscribe | ( | ) | [protected, virtual] |
Definition at line 163 of file map_display.cpp.
| void rviz::MapDisplay::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 253 of file map_display.cpp.
| void rviz::MapDisplay::updateAlpha | ( | ) | [protected, slot] |
Definition at line 168 of file map_display.cpp.
| void rviz::MapDisplay::updateDrawUnder | ( | ) | [protected, slot] |
Definition at line 197 of file map_display.cpp.
| void rviz::MapDisplay::updateTopic | ( | ) | [protected, slot] |
Definition at line 219 of file map_display.cpp.
FloatProperty* rviz::MapDisplay::alpha_property_ [protected] |
Definition at line 125 of file map_display.h.
nav_msgs::OccupancyGrid::ConstPtr rviz::MapDisplay::current_map_ [protected] |
Definition at line 129 of file map_display.h.
Property* rviz::MapDisplay::draw_under_property_ [protected] |
Definition at line 126 of file map_display.h.
std::string rviz::MapDisplay::frame_ [protected] |
Definition at line 115 of file map_display.h.
int rviz::MapDisplay::height_ [protected] |
Definition at line 112 of file map_display.h.
IntProperty* rviz::MapDisplay::height_property_ [protected] |
Definition at line 122 of file map_display.h.
bool rviz::MapDisplay::loaded_ [protected] |
Definition at line 107 of file map_display.h.
Ogre::ManualObject* rviz::MapDisplay::manual_object_ [protected] |
Definition at line 104 of file map_display.h.
ros::Subscriber rviz::MapDisplay::map_sub_ [protected] |
Definition at line 117 of file map_display.h.
Ogre::MaterialPtr rviz::MapDisplay::material_ [protected] |
Definition at line 106 of file map_display.h.
boost::mutex rviz::MapDisplay::mutex_ [protected] |
Definition at line 130 of file map_display.h.
bool rviz::MapDisplay::new_map_ [protected] |
Definition at line 131 of file map_display.h.
Ogre::Quaternion rviz::MapDisplay::orientation_ [protected] |
Definition at line 114 of file map_display.h.
Definition at line 124 of file map_display.h.
Ogre::Vector3 rviz::MapDisplay::position_ [protected] |
Definition at line 113 of file map_display.h.
VectorProperty* rviz::MapDisplay::position_property_ [protected] |
Definition at line 123 of file map_display.h.
float rviz::MapDisplay::resolution_ [protected] |
Definition at line 110 of file map_display.h.
FloatProperty* rviz::MapDisplay::resolution_property_ [protected] |
Definition at line 120 of file map_display.h.
Ogre::TexturePtr rviz::MapDisplay::texture_ [protected] |
Definition at line 105 of file map_display.h.
std::string rviz::MapDisplay::topic_ [protected] |
Definition at line 109 of file map_display.h.
RosTopicProperty* rviz::MapDisplay::topic_property_ [protected] |
Definition at line 119 of file map_display.h.
nav_msgs::OccupancyGrid::ConstPtr rviz::MapDisplay::updated_map_ [protected] |
Definition at line 128 of file map_display.h.
int rviz::MapDisplay::width_ [protected] |
Definition at line 111 of file map_display.h.
IntProperty* rviz::MapDisplay::width_property_ [protected] |
Definition at line 121 of file map_display.h.