22#ifndef EASYNAV_SENSORS_TYPES__DETECTIONSPERCEPTIONS_HPP_
23#define EASYNAV_SENSORS_TYPES__DETECTIONSPERCEPTIONS_HPP_
28#include "vision_msgs/msg/detection3_d_array.hpp"
30#include "rclcpp_lifecycle/lifecycle_node.hpp"
52 return t ==
"vision_msgs/msg/Detection3DArray";
57 [[maybe_unused]]
static const bool _ = [] {
60 std::ostringstream ret;
61 ret <<
"{ " << perception.
stamp.seconds()
62 <<
" } DetectionsPerception with "
63 << perception.
data.detections.size()
64 <<
" detections in frame [" << perception.
frame_id
65 <<
"] with ts " << perception.
stamp.seconds() <<
"\n";
73 vision_msgs::msg::Detection3DArray
data;
96 bool cycle_rt([[maybe_unused]] std::shared_ptr<NavState> nav_state)
override;
100 std::shared_ptr<DetectionsPerception> perception_data_ {
nullptr};
103 rclcpp::SubscriptionBase::SharedPtr perception_sub_;
113 std::vector<std::shared_ptr<DetectionsPerception>>;
Defines data structures and utilities for representing and processing sensor perceptions.
static bool supports_msg_type(std::string_view t)
Returns whether the given ROS 2 type name is supported by this perception.
Definition DetectionsPerception.hpp:50
DetectionsPerception()
Definition DetectionsPerception.hpp:55
static constexpr std::string_view default_group_
Group identifier for image perceptions.
Definition DetectionsPerception.hpp:45
vision_msgs::msg::Detection3DArray data
Detection3DArray data received from the an external processing system.
Definition DetectionsPerception.hpp:73
Handles the creation and updating of DetectionsPerceptions instances from sensor_msgs::msg::Image mes...
Definition DetectionsPerception.hpp:82
bool cycle_rt(std::shared_ptr< NavState > nav_state) override
Run one real-time sensor processing cycle.
Definition DetectionsPerception.cpp:72
void on_initialize() override
Optional post-initialization hook for subclasses.
Definition DetectionsPerception.cpp:28
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< DetectionsPerception > > DetectionsPerceptions
Definition DetectionsPerception.hpp:112
rclcpp::Time get_latest_detections_perceptions_stamp(const DetectionsPerceptions &perceptions)
Retrieves the latest timestamp among a set of detection-based perceptions.
Definition DetectionsPerception.cpp:82