Displays a map along the XZ plane (XY in robot space) More...
#include <map_display.h>
Public Member Functions | |
virtual void | createProperties () |
Called from setPropertyManager, gives the display a chance to create some properties immediately. | |
virtual void | fixedFrameChanged () |
Override to handle changes to fixed_frame_. This base class implementation does nothing. | |
float | getAlpha () |
bool | getDrawUnder () |
int | getHeight () |
Ogre::Quaternion | getOrientation () |
Ogre::Vector3 | getPosition () |
float | getResolution () |
const std::string & | getTopic () |
int | getWidth () |
virtual void | hideVisible () |
Hides all visible parts of this display, so they do not show up when the scene is rendered. | |
MapDisplay () | |
void | onInitialize () |
Override this function to do subclass-specific initialization. | |
virtual void | reset () |
Called to tell the display to clear its state. | |
virtual void | restoreVisible () |
Restores the display to the state it was in before hideVisible() was called. | |
void | setAlpha (float alpha) |
void | setDrawUnder (bool write) |
void | setTopic (const std::string &topic) |
virtual void | update (float wall_dt, float ros_dt) |
Called periodically by the visualization panel. | |
virtual | ~MapDisplay () |
Protected Member Functions | |
void | clear () |
void | incomingMap (const nav_msgs::OccupancyGrid::ConstPtr &msg) |
void | load (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. | |
void | requestThreadFunc () |
void | subscribe () |
void | transformMap () |
void | unsubscribe () |
Protected Attributes | |
float | alpha_ |
FloatPropertyWPtr | alpha_property_ |
bool | draw_under_ |
BoolPropertyWPtr | draw_under_property_ |
std::string | frame_ |
int | height_ |
IntPropertyWPtr | height_property_ |
bool | hidden_ |
bool | loaded_ |
Ogre::ManualObject * | manual_object_ |
nav_msgs::OccupancyGrid::ConstPtr | map_ |
ros::Subscriber | map_sub_ |
Ogre::MaterialPtr | material_ |
Ogre::Quaternion | orientation_ |
QuaternionPropertyWPtr | orientation_property_ |
Ogre::Vector3 | position_ |
Vector3PropertyWPtr | position_property_ |
float | resolution_ |
FloatPropertyWPtr | resolution_property_ |
Ogre::SceneNode * | scene_node_ |
Ogre::TexturePtr | texture_ |
std::string | topic_ |
ROSTopicStringPropertyWPtr | topic_property_ |
int | width_ |
IntPropertyWPtr | width_property_ |
Displays a map along the XZ plane (XY in robot space)
Definition at line 62 of file map_display.h.
Definition at line 54 of file map_display.cpp.
rviz::MapDisplay::~MapDisplay | ( | ) | [virtual] |
Definition at line 70 of file map_display.cpp.
void rviz::MapDisplay::clear | ( | void | ) | [protected] |
Definition at line 218 of file map_display.cpp.
void rviz::MapDisplay::createProperties | ( | ) | [virtual] |
Called from setPropertyManager, gives the display a chance to create some properties immediately.
When this function is called, the property_manager_ member is valid and will stay valid
Reimplemented from rviz::Display.
Definition at line 486 of file map_display.cpp.
void rviz::MapDisplay::fixedFrameChanged | ( | ) | [virtual] |
Override to handle changes to fixed_frame_. This base class implementation does nothing.
Reimplemented from rviz::Display.
Definition at line 519 of file map_display.cpp.
float rviz::MapDisplay::getAlpha | ( | ) | [inline] |
Definition at line 79 of file map_display.h.
bool rviz::MapDisplay::getDrawUnder | ( | ) | [inline] |
Definition at line 82 of file map_display.h.
int rviz::MapDisplay::getHeight | ( | ) | [inline] |
Definition at line 75 of file map_display.h.
Ogre::Quaternion rviz::MapDisplay::getOrientation | ( | ) | [inline] |
Definition at line 77 of file map_display.h.
Ogre::Vector3 rviz::MapDisplay::getPosition | ( | ) | [inline] |
Definition at line 76 of file map_display.h.
float rviz::MapDisplay::getResolution | ( | ) | [inline] |
Definition at line 73 of file map_display.h.
const std::string& rviz::MapDisplay::getTopic | ( | ) | [inline] |
Definition at line 71 of file map_display.h.
int rviz::MapDisplay::getWidth | ( | ) | [inline] |
Definition at line 74 of file map_display.h.
void rviz::MapDisplay::hideVisible | ( | ) | [virtual] |
Hides all visible parts of this display, so they do not show up when the scene is rendered.
Reimplemented from rviz::Display.
Definition at line 107 of file map_display.cpp.
void rviz::MapDisplay::incomingMap | ( | const nav_msgs::OccupancyGrid::ConstPtr & | msg | ) | [protected] |
Definition at line 533 of file map_display.cpp.
void rviz::MapDisplay::load | ( | const nav_msgs::OccupancyGrid::ConstPtr & | msg | ) | [protected] |
Definition at line 245 of file map_display.cpp.
void rviz::MapDisplay::onDisable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of disabling themselves.
Implements rviz::Display.
Definition at line 100 of file map_display.cpp.
void rviz::MapDisplay::onEnable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of enabling themselves.
Implements rviz::Display.
Definition at line 94 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.
Reimplemented from rviz::Display.
Definition at line 77 of file map_display.cpp.
void rviz::MapDisplay::requestThreadFunc | ( | ) | [protected] |
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::restoreVisible | ( | ) | [virtual] |
Restores the display to the state it was in before hideVisible() was called.
Reimplemented from rviz::Display.
Definition at line 113 of file map_display.cpp.
void rviz::MapDisplay::setAlpha | ( | float | alpha | ) |
Definition at line 145 of file map_display.cpp.
void rviz::MapDisplay::setDrawUnder | ( | bool | write | ) |
Definition at line 176 of file map_display.cpp.
void rviz::MapDisplay::setTopic | ( | const std::string & | topic | ) |
Definition at line 199 of file map_display.cpp.
void rviz::MapDisplay::subscribe | ( | ) | [protected] |
Definition at line 119 of file map_display.cpp.
void rviz::MapDisplay::transformMap | ( | ) | [protected] |
Definition at line 456 of file map_display.cpp.
void rviz::MapDisplay::unsubscribe | ( | ) | [protected] |
Definition at line 140 of file map_display.cpp.
void rviz::MapDisplay::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 482 of file map_display.cpp.
float rviz::MapDisplay::alpha_ [protected] |
Definition at line 128 of file map_display.h.
FloatPropertyWPtr rviz::MapDisplay::alpha_property_ [protected] |
Definition at line 139 of file map_display.h.
bool rviz::MapDisplay::draw_under_ [protected] |
Definition at line 129 of file map_display.h.
BoolPropertyWPtr rviz::MapDisplay::draw_under_property_ [protected] |
Definition at line 140 of file map_display.h.
std::string rviz::MapDisplay::frame_ [protected] |
Definition at line 125 of file map_display.h.
int rviz::MapDisplay::height_ [protected] |
Definition at line 122 of file map_display.h.
IntPropertyWPtr rviz::MapDisplay::height_property_ [protected] |
Definition at line 136 of file map_display.h.
bool rviz::MapDisplay::hidden_ [protected] |
Definition at line 142 of file map_display.h.
bool rviz::MapDisplay::loaded_ [protected] |
Definition at line 117 of file map_display.h.
Ogre::ManualObject* rviz::MapDisplay::manual_object_ [protected] |
Definition at line 114 of file map_display.h.
nav_msgs::OccupancyGrid::ConstPtr rviz::MapDisplay::map_ [protected] |
Definition at line 126 of file map_display.h.
ros::Subscriber rviz::MapDisplay::map_sub_ [protected] |
Definition at line 131 of file map_display.h.
Ogre::MaterialPtr rviz::MapDisplay::material_ [protected] |
Definition at line 116 of file map_display.h.
Ogre::Quaternion rviz::MapDisplay::orientation_ [protected] |
Definition at line 124 of file map_display.h.
QuaternionPropertyWPtr rviz::MapDisplay::orientation_property_ [protected] |
Definition at line 138 of file map_display.h.
Ogre::Vector3 rviz::MapDisplay::position_ [protected] |
Definition at line 123 of file map_display.h.
Vector3PropertyWPtr rviz::MapDisplay::position_property_ [protected] |
Definition at line 137 of file map_display.h.
float rviz::MapDisplay::resolution_ [protected] |
Definition at line 120 of file map_display.h.
FloatPropertyWPtr rviz::MapDisplay::resolution_property_ [protected] |
Definition at line 134 of file map_display.h.
Ogre::SceneNode* rviz::MapDisplay::scene_node_ [protected] |
Definition at line 113 of file map_display.h.
Ogre::TexturePtr rviz::MapDisplay::texture_ [protected] |
Definition at line 115 of file map_display.h.
std::string rviz::MapDisplay::topic_ [protected] |
Definition at line 119 of file map_display.h.
ROSTopicStringPropertyWPtr rviz::MapDisplay::topic_property_ [protected] |
Definition at line 133 of file map_display.h.
int rviz::MapDisplay::width_ [protected] |
Definition at line 121 of file map_display.h.
IntPropertyWPtr rviz::MapDisplay::width_property_ [protected] |
Definition at line 135 of file map_display.h.