27#ifndef EASYNAV_COMMON_TYPES__IMUPERCEPTIONS_HPP_
28#define EASYNAV_COMMON_TYPES__IMUPERCEPTIONS_HPP_
33#include "sensor_msgs/msg/imu.hpp"
35#include "rclcpp_lifecycle/lifecycle_node.hpp"
57 return t ==
"sensor_msgs/msg/Imu";
61 sensor_msgs::msg::Imu
data;
73 std::string
group()
const override {
return "imu";}
78 std::shared_ptr<PerceptionBase>
create(
const std::string &)
override
80 return std::make_shared<IMUPerception>();
95 rclcpp_lifecycle::LifecycleNode & node,
96 const std::string & topic,
97 const std::string & type,
98 std::shared_ptr<PerceptionBase> target,
99 rclcpp::CallbackGroup::SharedPtr cb_group)
override;
109 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:69
std::shared_ptr< PerceptionBase > create(const std::string &) override
Creates a new empty IMUPerception instance.
Definition IMUPerception.hpp:78
std::string group() const override
Returns the group managed by this handler.
Definition IMUPerception.hpp:73
rclcpp::SubscriptionBase::SharedPtr create_subscription(rclcpp_lifecycle::LifecycleNode &node, const std::string &topic, const std::string &type, std::shared_ptr< PerceptionBase > target, rclcpp::CallbackGroup::SharedPtr cb_group) override
Creates a subscription to an IMU topic that updates a target IMUPerception.
Definition IMUPerception.cpp:35
Represents a single IMU perception from a sensor.
Definition IMUPerception.hpp:47
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:55
static constexpr std::string_view default_group_
Group identifier for IMU perceptions.
Definition IMUPerception.hpp:50
sensor_msgs::msg::Imu data
IMU data received from the sensor.
Definition IMUPerception.hpp:61
Abstract base class for representing a single sensor perception.
Definition Perceptions.hpp:45
Abstract base interface for group-specific perception handlers.
Definition Perceptions.hpp:121
Definition CircularBuffer.hpp:28
std::vector< std::shared_ptr< IMUPerception > > IMUPerceptions
Alias for a vector of shared pointers to IMUPerception objects.
Definition IMUPerception.hpp:108
rclcpp::Time get_latest_imu_perceptions_stamp(const IMUPerceptions &perceptions)
Retrieves the latest timestamp among a set of IMU perceptions.
Definition IMUPerception.cpp:64