20 #ifndef LOCALIZATION_RVIZ_PLUGINS_POSE_DISPLAY_H_ // NOLINT
21 #define LOCALIZATION_RVIZ_PLUGINS_POSE_DISPLAY_H_ // NOLINT
25 #include <geometry_msgs/PoseStamped.h>
26 #include <rviz/message_filter_display.h>
27 #include <rviz/ogre_helpers/axes.h>
28 #include <rviz/properties/float_property.h>
29 #include <rviz/properties/int_property.h>
30 #include <boost/circular_buffer.hpp>
42 class PoseDisplay :
public rviz::MessageFilterDisplay<geometry_msgs::PoseStamped> {
55 void processMessage(
const geometry_msgs::PoseStamped::ConstPtr& msg);
58 boost::circular_buffer<std::unique_ptr<rviz::Axes>> pose_axes_;
59 std::unique_ptr<rviz::FloatProperty> pose_axes_size_;
60 std::unique_ptr<rviz::IntProperty> number_of_poses_;
63 #endif // LOCALIZATION_RVIZ_PLUGINS_POSE_DISPLAY_H_ NOLINT