31 #ifndef RVIZ_ODOMETRY_DISPLAY_H_ 32 #define RVIZ_ODOMETRY_DISPLAY_H_ 36 #include <boost/shared_ptr.hpp> 37 #include <boost/thread/mutex.hpp> 44 #include <nav_msgs/Odometry.h> 55 class CovarianceProperty;
76 void reset()
override;
78 void update(
float wall_dt,
float ros_dt)
override;
96 void processMessage(
const nav_msgs::Odometry::ConstPtr& message)
override;
99 typedef std::deque<rviz::Axes*>
D_Axes;
std::deque< rviz::Axes * > D_Axes
nav_msgs::Odometry::ConstPtr last_used_message_
void onInitialize() override
Override this function to do subclass-specific initialization.
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
void updateShapeVisibility()
void onEnable() override
Overridden from MessageFilterDisplay to get Arrow/Axes visibility correct.
rviz::FloatProperty * head_length_property_
~OdometryDisplay() override
void updateColorAndAlpha()
rviz::FloatProperty * axes_radius_property_
Property specialized to enforce floating point max/min.
Property specialized to provide max/min enforcement for integers.
rviz::FloatProperty * position_tolerance_property_
rviz::FloatProperty * shaft_length_property_
rviz::EnumProperty * shape_property_
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
void reset() override
Called to tell the display to clear its state.
Accumulates and displays the pose from a nav_msgs::Odometry message.
rviz::FloatProperty * angle_tolerance_property_
void updateGeometry(rviz::Arrow *arrow)
CovarianceProperty * covariance_property_
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
void processMessage(const nav_msgs::Odometry::ConstPtr &message) override
std::deque< rviz::Arrow * > D_Arrow
rviz::IntProperty * keep_property_
Property specialized to provide getter for booleans.
rviz::FloatProperty * alpha_property_
An arrow consisting of a cylinder and a cone.
rviz::FloatProperty * axes_length_property_
rviz::ColorProperty * color_property_
rviz::FloatProperty * head_radius_property_
void updateAxisGeometry()
void updateArrowsGeometry()
rviz::FloatProperty * shaft_radius_property_