rviz::MapDisplay Class Reference

Displays a map along the XZ plane (XY in robot space). More...

#include <map_display.h>

Inheritance diagram for rviz::MapDisplay:
Inheritance graph
[legend]

List of all members.

Public Member Functions

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 ()
bool getDrawUnder ()
float getHeight ()
Ogre::Quaternion getOrientation ()
Ogre::Vector3 getPosition ()
float getResolution ()
const std::string & getTopic ()
float getWidth ()
 MapDisplay (const std::string &name, VisualizationManager *manager)
virtual void reset ()
 Called to tell the display to clear its state.
void setAlpha (float alpha)
void setDrawUnder (bool write)
void setTopic (const std::string &topic)
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 ~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_
float height_
FloatPropertyWPtr height_property_
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_
float width_
FloatPropertyWPtr width_property_

Detailed Description

Displays a map along the XZ plane (XY in robot space).

Definition at line 62 of file map_display.h.


Constructor & Destructor Documentation

rviz::MapDisplay::MapDisplay ( const std::string &  name,
VisualizationManager manager 
)

Definition at line 55 of file map_display.cpp.

rviz::MapDisplay::~MapDisplay (  )  [virtual]

Definition at line 81 of file map_display.cpp.


Member Function Documentation

void rviz::MapDisplay::clear (  )  [protected]

Definition at line 194 of file map_display.cpp.

void rviz::MapDisplay::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 446 of file map_display.cpp.

void rviz::MapDisplay::fixedFrameChanged (  )  [virtual]

Called from within setFixedFrame, notifying child classes that the fixed frame has changed.

Implements rviz::Display.

Definition at line 479 of file map_display.cpp.

float rviz::MapDisplay::getAlpha (  )  [inline]

Definition at line 77 of file map_display.h.

bool rviz::MapDisplay::getDrawUnder (  )  [inline]

Definition at line 80 of file map_display.h.

float rviz::MapDisplay::getHeight (  )  [inline]

Definition at line 73 of file map_display.h.

Ogre::Quaternion rviz::MapDisplay::getOrientation (  )  [inline]

Definition at line 75 of file map_display.h.

Ogre::Vector3 rviz::MapDisplay::getPosition (  )  [inline]

Definition at line 74 of file map_display.h.

float rviz::MapDisplay::getResolution (  )  [inline]

Definition at line 71 of file map_display.h.

const std::string& rviz::MapDisplay::getTopic (  )  [inline]

Definition at line 69 of file map_display.h.

float rviz::MapDisplay::getWidth (  )  [inline]

Definition at line 72 of file map_display.h.

void rviz::MapDisplay::incomingMap ( const nav_msgs::OccupancyGrid::ConstPtr &  msg  )  [protected]

Definition at line 493 of file map_display.cpp.

void rviz::MapDisplay::load ( const nav_msgs::OccupancyGrid::ConstPtr &  msg  )  [protected]

Definition at line 221 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 95 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 88 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 484 of file map_display.cpp.

void rviz::MapDisplay::setAlpha ( float  alpha  ) 

Definition at line 121 of file map_display.cpp.

void rviz::MapDisplay::setDrawUnder ( bool  write  ) 

Definition at line 152 of file map_display.cpp.

void rviz::MapDisplay::setTopic ( const std::string &  topic  ) 

Definition at line 175 of file map_display.cpp.

void rviz::MapDisplay::subscribe (  )  [protected]

Definition at line 103 of file map_display.cpp.

virtual void rviz::MapDisplay::targetFrameChanged (  )  [inline, virtual]

Called from within setTargetFrame, notifying child classes that the target frame has changed.

Implements rviz::Display.

Definition at line 84 of file map_display.h.

void rviz::MapDisplay::transformMap (  )  [protected]

Definition at line 416 of file map_display.cpp.

void rviz::MapDisplay::unsubscribe (  )  [protected]

Definition at line 116 of file map_display.cpp.

void rviz::MapDisplay::update ( float  wall_dt,
float  ros_dt 
) [virtual]

Called periodically by the visualization panel.

Parameters:
dt Wall-clock time, in seconds, since the last time the update list was run through.

Reimplemented from rviz::Display.

Definition at line 442 of file map_display.cpp.


Member Data Documentation

float rviz::MapDisplay::alpha_ [protected]

Definition at line 121 of file map_display.h.

FloatPropertyWPtr rviz::MapDisplay::alpha_property_ [protected]

Definition at line 132 of file map_display.h.

Definition at line 122 of file map_display.h.

BoolPropertyWPtr rviz::MapDisplay::draw_under_property_ [protected]

Definition at line 133 of file map_display.h.

std::string rviz::MapDisplay::frame_ [protected]

Definition at line 118 of file map_display.h.

float rviz::MapDisplay::height_ [protected]

Definition at line 115 of file map_display.h.

FloatPropertyWPtr rviz::MapDisplay::height_property_ [protected]

Definition at line 129 of file map_display.h.

bool rviz::MapDisplay::loaded_ [protected]

Definition at line 110 of file map_display.h.

Ogre::ManualObject* rviz::MapDisplay::manual_object_ [protected]

Definition at line 107 of file map_display.h.

nav_msgs::OccupancyGrid::ConstPtr rviz::MapDisplay::map_ [protected]

Definition at line 119 of file map_display.h.

ros::Subscriber rviz::MapDisplay::map_sub_ [protected]

Definition at line 124 of file map_display.h.

Ogre::MaterialPtr rviz::MapDisplay::material_ [protected]

Definition at line 109 of file map_display.h.

Ogre::Quaternion rviz::MapDisplay::orientation_ [protected]

Definition at line 117 of file map_display.h.

QuaternionPropertyWPtr rviz::MapDisplay::orientation_property_ [protected]

Definition at line 131 of file map_display.h.

Ogre::Vector3 rviz::MapDisplay::position_ [protected]

Definition at line 116 of file map_display.h.

Vector3PropertyWPtr rviz::MapDisplay::position_property_ [protected]

Definition at line 130 of file map_display.h.

float rviz::MapDisplay::resolution_ [protected]

Definition at line 113 of file map_display.h.

FloatPropertyWPtr rviz::MapDisplay::resolution_property_ [protected]

Definition at line 127 of file map_display.h.

Ogre::SceneNode* rviz::MapDisplay::scene_node_ [protected]

Definition at line 106 of file map_display.h.

Ogre::TexturePtr rviz::MapDisplay::texture_ [protected]

Definition at line 108 of file map_display.h.

std::string rviz::MapDisplay::topic_ [protected]

Definition at line 112 of file map_display.h.

ROSTopicStringPropertyWPtr rviz::MapDisplay::topic_property_ [protected]

Definition at line 126 of file map_display.h.

float rviz::MapDisplay::width_ [protected]

Definition at line 114 of file map_display.h.

FloatPropertyWPtr rviz::MapDisplay::width_property_ [protected]

Definition at line 128 of file map_display.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


rviz
Author(s): Josh Faust
autogenerated on Fri Jan 11 09:36:32 2013