Easy Navigation
Loading...
Searching...
No Matches
IMUPerception.hpp
Go to the documentation of this file.
1// Copyright 2025 Intelligent Robotics Lab
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
21
22#ifndef EASYNAV_SENSORS_TYPES__IMUPERCEPTIONS_HPP_
23#define EASYNAV_SENSORS_TYPES__IMUPERCEPTIONS_HPP_
24
25#include <string>
26#include <vector>
27
28#include "sensor_msgs/msg/imu.hpp"
29
30#include "rclcpp_lifecycle/lifecycle_node.hpp"
31
33
34namespace easynav
35{
36
42{
43public:
45 static constexpr std::string_view default_group_ = "imu";
46
50 static inline bool supports_msg_type(std::string_view t)
51 {
52 return t == "sensor_msgs/msg/Imu";
53 }
54
56 {
57 [[maybe_unused]] static const bool _ = [] {
59 [](const IMUPerception & perception) {
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";
68 return ret.str();
69 });
70 return true;
71 }();
72 }
73
75 sensor_msgs::msg::Imu data;
76};
77
83{
84public:
88 void on_initialize() override;
89
97 bool cycle_rt([[maybe_unused]] std::shared_ptr<NavState> nav_state) override;
98
99private:
101 std::shared_ptr<IMUPerception> perception_data_ {nullptr};
102
104 rclcpp::SubscriptionBase::SharedPtr perception_sub_;
105};
106
114 std::vector<std::shared_ptr<IMUPerception>>;
115
119rclcpp::Time get_latest_imu_perceptions_stamp(const IMUPerceptions & perceptions);
120
121} // namespace easynav
122
123#endif // EASYNAV_SENSORS_TYPES__IMUPERCEPTIONS_HPP_
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