Signals | Public Member Functions | Protected Slots | Protected Member Functions | Protected Attributes
rviz::MapDisplay Class Reference

Displays a map along the XY plane. More...

#include <map_display.h>

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

List of all members.

Signals

void mapUpdated ()
 Emitted when a new map is received.

Public Member Functions

virtual void fixedFrameChanged ()
 Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
int getHeight ()
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 setTopic (const QString &topic, const QString &datatype)
 Set the ROS topic to listen to for this display.
virtual ~MapDisplay ()

Protected Slots

void showMap ()
 Show current_map_ in the scene.
void updateAlpha ()
void updateDrawUnder ()
void updatePalette ()
void updateTopic ()

Protected Member Functions

void clear ()
void incomingMap (const nav_msgs::OccupancyGrid::ConstPtr &msg)
 Copy msg into current_map_ and call showMap().
void incomingUpdate (const map_msgs::OccupancyGridUpdate::ConstPtr &update)
 Copy update's data into current_map_ and call showMap().
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 ()
virtual void update (float wall_dt, float ros_dt)
 Called periodically by the visualization manager.

Protected Attributes

FloatPropertyalpha_property_
EnumPropertycolor_scheme_property_
std::vector< bool > color_scheme_transparency_
nav_msgs::OccupancyGrid current_map_
Propertydraw_under_property_
std::string frame_
int height_
IntPropertyheight_property_
bool loaded_
Ogre::ManualObject * manual_object_
ros::Subscriber map_sub_
Ogre::MaterialPtr material_
QuaternionPropertyorientation_property_
std::vector< Ogre::TexturePtr > palette_textures_
VectorPropertyposition_property_
float resolution_
FloatPropertyresolution_property_
Ogre::TexturePtr texture_
std::string topic_
RosTopicPropertytopic_property_
BoolPropertyunreliable_property_
ros::Subscriber update_sub_
int width_
IntPropertywidth_property_

Detailed Description

Displays a map along the XY plane.

Definition at line 70 of file map_display.h.


Constructor & Destructor Documentation

Definition at line 62 of file map_display.cpp.

Definition at line 122 of file map_display.cpp.


Member Function Documentation

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

Definition at line 452 of file map_display.cpp.

Called by setFixedFrame(). Override to respond to changes to fixed_frame_.

Reimplemented from rviz::Display.

Definition at line 724 of file map_display.cpp.

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

Definition at line 84 of file map_display.h.

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

Definition at line 82 of file map_display.h.

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

Definition at line 83 of file map_display.h.

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

Copy msg into current_map_ and call showMap().

Definition at line 483 of file map_display.cpp.

void rviz::MapDisplay::incomingUpdate ( const map_msgs::OccupancyGridUpdate::ConstPtr &  update) [protected]

Copy update's data into current_map_ and call showMap().

Definition at line 492 of file map_display.cpp.

void rviz::MapDisplay::mapUpdated ( ) [signal]

Emitted when a new map is received.

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 334 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 329 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 249 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 729 of file map_display.cpp.

void rviz::MapDisplay::setTopic ( const QString &  topic,
const QString &  datatype 
) [virtual]

Set the ROS topic to listen to for this display.

By default, do nothing. Subclasses should override this method if they subscribe to a single ROS topic.

setTopic() is used by the "New display by topic" window; it is called with a user selected topic and its type.

Parameters:
topicThe published topic to be visualized.
datatypeThe datatype of the topic.

Reimplemented from rviz::Display.

Definition at line 738 of file map_display.cpp.

void rviz::MapDisplay::showMap ( ) [protected, slot]

Show current_map_ in the scene.

Definition at line 521 of file map_display.cpp.

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

Definition at line 340 of file map_display.cpp.

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

Definition at line 698 of file map_display.cpp.

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

Definition at line 376 of file map_display.cpp.

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

Called periodically by the visualization manager.

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

Reimplemented from rviz::Display.

Definition at line 743 of file map_display.cpp.

void rviz::MapDisplay::updateAlpha ( ) [protected, slot]

Definition at line 398 of file map_display.cpp.

void rviz::MapDisplay::updateDrawUnder ( ) [protected, slot]

Definition at line 423 of file map_display.cpp.

void rviz::MapDisplay::updatePalette ( ) [protected, slot]

Definition at line 678 of file map_display.cpp.

void rviz::MapDisplay::updateTopic ( ) [protected, slot]

Definition at line 445 of file map_display.cpp.


Member Data Documentation

Definition at line 142 of file map_display.h.

Definition at line 144 of file map_display.h.

std::vector<bool> rviz::MapDisplay::color_scheme_transparency_ [protected]

Definition at line 122 of file map_display.h.

nav_msgs::OccupancyGrid rviz::MapDisplay::current_map_ [protected]

Definition at line 131 of file map_display.h.

Definition at line 143 of file map_display.h.

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

Definition at line 130 of file map_display.h.

int rviz::MapDisplay::height_ [protected]

Definition at line 129 of file map_display.h.

Definition at line 139 of file map_display.h.

bool rviz::MapDisplay::loaded_ [protected]

Definition at line 124 of file map_display.h.

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

Definition at line 119 of file map_display.h.

Definition at line 133 of file map_display.h.

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

Definition at line 123 of file map_display.h.

Definition at line 141 of file map_display.h.

std::vector<Ogre::TexturePtr> rviz::MapDisplay::palette_textures_ [protected]

Definition at line 121 of file map_display.h.

Definition at line 140 of file map_display.h.

float rviz::MapDisplay::resolution_ [protected]

Definition at line 127 of file map_display.h.

Definition at line 137 of file map_display.h.

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

Definition at line 120 of file map_display.h.

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

Definition at line 126 of file map_display.h.

Definition at line 136 of file map_display.h.

Definition at line 146 of file map_display.h.

Definition at line 134 of file map_display.h.

int rviz::MapDisplay::width_ [protected]

Definition at line 128 of file map_display.h.

Definition at line 138 of file map_display.h.


The documentation for this class was generated from the following files:


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Jun 6 2019 18:02:17