Public Member Functions | Protected Member Functions | Private Types | Private Slots | Private Member Functions | Private Attributes
rviz::OdometryDisplay Class Reference

Accumulates and displays the pose from a nav_msgs::Odometry message. More...

#include <odometry_display.h>

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

List of all members.

Public Member Functions

virtual void fixedFrameChanged ()
 Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
 OdometryDisplay ()
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 ~OdometryDisplay ()

Protected Member Functions

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.

Private Types

typedef std::deque< Arrow * > D_Arrow

Private Slots

void updateColor ()
void updateLength ()
void updateTopic ()

Private Member Functions

void clear ()
void incomingMessage (const nav_msgs::Odometry::ConstPtr &message)
void subscribe ()
void transformArrow (const nav_msgs::Odometry::ConstPtr &message, Arrow *arrow)
void unsubscribe ()

Private Attributes

FloatPropertyangle_tolerance_property_
D_Arrow arrows_
ColorPropertycolor_property_
IntPropertykeep_property_
nav_msgs::Odometry::ConstPtr last_used_message_
FloatPropertylength_property_
uint32_t messages_received_
FloatPropertyposition_tolerance_property_
message_filters::Subscriber
< nav_msgs::Odometry > 
sub_
tf::MessageFilter
< nav_msgs::Odometry > * 
tf_filter_
RosTopicPropertytopic_property_

Detailed Description

Accumulates and displays the pose from a nav_msgs::Odometry message.

Definition at line 61 of file odometry_display.h.


Member Typedef Documentation

typedef std::deque<Arrow*> rviz::OdometryDisplay::D_Arrow [private]

Definition at line 92 of file odometry_display.h.


Constructor & Destructor Documentation

Definition at line 49 of file odometry_display.cpp.

Definition at line 84 of file odometry_display.cpp.


Member Function Documentation

void rviz::OdometryDisplay::clear ( ) [private]

Definition at line 101 of file odometry_display.cpp.

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

Reimplemented from rviz::Display.

Definition at line 263 of file odometry_display.cpp.

void rviz::OdometryDisplay::incomingMessage ( const nav_msgs::Odometry::ConstPtr &  message) [private]

Definition at line 203 of file odometry_display.cpp.

void rviz::OdometryDisplay::onDisable ( ) [protected, virtual]

Derived classes override this to do the actual work of disabling themselves.

Reimplemented from rviz::Display.

Definition at line 189 of file odometry_display.cpp.

void rviz::OdometryDisplay::onEnable ( ) [protected, virtual]

Derived classes override this to do the actual work of enabling themselves.

Reimplemented from rviz::Display.

Definition at line 184 of file odometry_display.cpp.

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 91 of file odometry_display.cpp.

void rviz::OdometryDisplay::reset ( ) [virtual]

Called to tell the display to clear its state.

Reimplemented from rviz::Display.

Definition at line 282 of file odometry_display.cpp.

Definition at line 161 of file odometry_display.cpp.

void rviz::OdometryDisplay::transformArrow ( const nav_msgs::Odometry::ConstPtr &  message,
Arrow *  arrow 
) [private]

Definition at line 246 of file odometry_display.cpp.

Definition at line 179 of file odometry_display.cpp.

void rviz::OdometryDisplay::update ( float  wall_dt,
float  ros_dt 
) [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 269 of file odometry_display.cpp.

void rviz::OdometryDisplay::updateColor ( ) [private, slot]

Definition at line 130 of file odometry_display.cpp.

void rviz::OdometryDisplay::updateLength ( ) [private, slot]

Definition at line 147 of file odometry_display.cpp.

void rviz::OdometryDisplay::updateTopic ( ) [private, slot]

Definition at line 122 of file odometry_display.cpp.


Member Data Documentation

Definition at line 104 of file odometry_display.h.

Definition at line 93 of file odometry_display.h.

Definition at line 101 of file odometry_display.h.

Definition at line 105 of file odometry_display.h.

nav_msgs::Odometry::ConstPtr rviz::OdometryDisplay::last_used_message_ [private]

Definition at line 97 of file odometry_display.h.

Definition at line 106 of file odometry_display.h.

Definition at line 95 of file odometry_display.h.

Definition at line 103 of file odometry_display.h.

Definition at line 98 of file odometry_display.h.

tf::MessageFilter<nav_msgs::Odometry>* rviz::OdometryDisplay::tf_filter_ [private]

Definition at line 99 of file odometry_display.h.

Definition at line 102 of file odometry_display.h.


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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:37