20 #ifndef LOCALIZATION_RVIZ_PLUGINS_IMU_AUGMENTOR_DISPLAY_H_ // NOLINT
21 #define LOCALIZATION_RVIZ_PLUGINS_IMU_AUGMENTOR_DISPLAY_H_ // NOLINT
25 #include <ff_msgs/EkfState.h>
26 #include <gtsam/geometry/Pose3.h>
27 #include <rviz/message_filter_display.h>
28 #include <rviz/ogre_helpers/arrow.h>
29 #include <rviz/ogre_helpers/axes.h>
30 #include <rviz/properties/float_property.h>
31 #include <rviz/properties/int_property.h>
32 #include <boost/circular_buffer.hpp>
56 void processMessage(
const ff_msgs::EkfState::ConstPtr& imu_augmentor_msg);
59 boost::circular_buffer<std::unique_ptr<rviz::Axes>> imu_augmentor_pose_axes_;
60 std::unique_ptr<rviz::Arrow> imu_acceleration_arrow_;
61 std::unique_ptr<rviz::BoolProperty> show_pose_axes_;
62 std::unique_ptr<rviz::FloatProperty> pose_axes_size_;
63 std::unique_ptr<rviz::IntProperty> number_of_poses_;
64 std::unique_ptr<rviz::BoolProperty> show_imu_acceleration_arrow_;
65 std::unique_ptr<rviz::FloatProperty> imu_acceleration_arrow_scale_;
68 #endif // LOCALIZATION_RVIZ_PLUGINS_IMU_AUGMENTOR_DISPLAY_H_ NOLINT