Accumulates and displays the pose from a nav_msgs::Odometry message. More...
#include <odometry_display.h>
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 | setTopic (const QString &topic, const QString &datatype) |
Set the ROS topic to listen to for this display. | |
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 | |
FloatProperty * | angle_tolerance_property_ |
D_Arrow | arrows_ |
ColorProperty * | color_property_ |
IntProperty * | keep_property_ |
nav_msgs::Odometry::ConstPtr | last_used_message_ |
FloatProperty * | length_property_ |
uint32_t | messages_received_ |
FloatProperty * | position_tolerance_property_ |
message_filters::Subscriber < nav_msgs::Odometry > | sub_ |
tf::MessageFilter < nav_msgs::Odometry > * | tf_filter_ |
RosTopicProperty * | topic_property_ |
Accumulates and displays the pose from a nav_msgs::Odometry message.
Definition at line 61 of file odometry_display.h.
typedef std::deque<Arrow*> rviz::OdometryDisplay::D_Arrow [private] |
Definition at line 94 of file odometry_display.h.
Definition at line 49 of file odometry_display.cpp.
rviz::OdometryDisplay::~OdometryDisplay | ( | ) | [virtual] |
Definition at line 84 of file odometry_display.cpp.
void rviz::OdometryDisplay::clear | ( | ) | [private] |
Definition at line 104 of file odometry_display.cpp.
void rviz::OdometryDisplay::fixedFrameChanged | ( | ) | [virtual] |
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
Reimplemented from rviz::Display.
Definition at line 266 of file odometry_display.cpp.
void rviz::OdometryDisplay::incomingMessage | ( | const nav_msgs::Odometry::ConstPtr & | message | ) | [private] |
Definition at line 206 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 192 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 187 of file odometry_display.cpp.
void rviz::OdometryDisplay::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 94 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 285 of file odometry_display.cpp.
void rviz::OdometryDisplay::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.
topic | The published topic to be visualized. |
datatype | The datatype of the topic. |
Reimplemented from rviz::Display.
Definition at line 291 of file odometry_display.cpp.
void rviz::OdometryDisplay::subscribe | ( | ) | [private] |
Definition at line 164 of file odometry_display.cpp.
void rviz::OdometryDisplay::transformArrow | ( | const nav_msgs::Odometry::ConstPtr & | message, |
Arrow * | arrow | ||
) | [private] |
Definition at line 249 of file odometry_display.cpp.
void rviz::OdometryDisplay::unsubscribe | ( | ) | [private] |
Definition at line 182 of file odometry_display.cpp.
void rviz::OdometryDisplay::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 272 of file odometry_display.cpp.
void rviz::OdometryDisplay::updateColor | ( | ) | [private, slot] |
Definition at line 133 of file odometry_display.cpp.
void rviz::OdometryDisplay::updateLength | ( | ) | [private, slot] |
Definition at line 150 of file odometry_display.cpp.
void rviz::OdometryDisplay::updateTopic | ( | ) | [private, slot] |
Definition at line 125 of file odometry_display.cpp.
Definition at line 106 of file odometry_display.h.
D_Arrow rviz::OdometryDisplay::arrows_ [private] |
Definition at line 95 of file odometry_display.h.
Definition at line 103 of file odometry_display.h.
IntProperty* rviz::OdometryDisplay::keep_property_ [private] |
Definition at line 107 of file odometry_display.h.
nav_msgs::Odometry::ConstPtr rviz::OdometryDisplay::last_used_message_ [private] |
Definition at line 99 of file odometry_display.h.
Definition at line 108 of file odometry_display.h.
uint32_t rviz::OdometryDisplay::messages_received_ [private] |
Definition at line 97 of file odometry_display.h.
Definition at line 105 of file odometry_display.h.
message_filters::Subscriber<nav_msgs::Odometry> rviz::OdometryDisplay::sub_ [private] |
Definition at line 100 of file odometry_display.h.
tf::MessageFilter<nav_msgs::Odometry>* rviz::OdometryDisplay::tf_filter_ [private] |
Definition at line 101 of file odometry_display.h.
Definition at line 104 of file odometry_display.h.