22#ifndef EASYNAV_SENSORS_TYPES__IMUPERCEPTIONS_HPP_
23#define EASYNAV_SENSORS_TYPES__IMUPERCEPTIONS_HPP_
28#include "sensor_msgs/msg/imu.hpp"
30#include "rclcpp_lifecycle/lifecycle_node.hpp"
52 return t ==
"sensor_msgs/msg/Imu";
57 [[maybe_unused]]
static const bool _ = [] {
60 std::ostringstream ret;
61 ret <<
"{ " << perception.
stamp.seconds()
62 <<
" } IMUPerception linear acc = ("
63 << perception.
data.linear_acceleration.x <<
", "
64 << perception.
data.linear_acceleration.y <<
", "
65 << perception.
data.linear_acceleration.z
66 <<
") in frame [" << perception.
frame_id
67 <<
"] with ts " << perception.
stamp.seconds() <<
"\n";
75 sensor_msgs::msg::Imu
data;
97 bool cycle_rt([[maybe_unused]] std::shared_ptr<NavState> nav_state)
override;
101 std::shared_ptr<IMUPerception> perception_data_ {
nullptr};
104 rclcpp::SubscriptionBase::SharedPtr perception_sub_;
114 std::vector<std::shared_ptr<IMUPerception>>;
Defines data structures and utilities for representing and processing sensor perceptions.
Handles the creation and updating of IMUPerception instances from sensor_msgs::msg::Imu messages.
Definition IMUPerception.hpp:83
bool cycle_rt(std::shared_ptr< NavState > nav_state) override
Run one real-time sensor processing cycle.
Definition IMUPerception.cpp:71
void on_initialize() override
Optional post-initialization hook for subclasses.
Definition IMUPerception.cpp:29
static bool supports_msg_type(std::string_view t)
Returns whether the given ROS 2 type name is supported by this perception.
Definition IMUPerception.hpp:50
static constexpr std::string_view default_group_
Group identifier for IMU perceptions.
Definition IMUPerception.hpp:45
sensor_msgs::msg::Imu data
IMU data received from the sensor.
Definition IMUPerception.hpp:75
IMUPerception()
Definition IMUPerception.hpp:55
static void register_printer(std::function< std::string(const T &)> printer)
Registers a pretty-printer for type T used by debug_string().
Definition NavState.hpp:384
Abstract base class for representing a single sensor perception.
Definition Perceptions.hpp:44
rclcpp::Time stamp
Timestamp of the perception (ROS time).
Definition Perceptions.hpp:49
std::string frame_id
Coordinate frame associated with the perception.
Definition Perceptions.hpp:52
Abstract base class for pluginlib-based sensor perception handlers.
Definition Perceptions.hpp:108
Definition CircularBuffer.hpp:23
std::vector< std::shared_ptr< IMUPerception > > IMUPerceptions
Alias for a vector of shared pointers to IMUPerception objects.
Definition IMUPerception.hpp:113
rclcpp::Time get_latest_imu_perceptions_stamp(const IMUPerceptions &perceptions)
Retrieves the latest timestamp among a set of IMU perceptions.
Definition IMUPerception.cpp:81