Easy Navigation
Loading...
Searching...
No Matches
GNSSPerception.hpp
Go to the documentation of this file.
1// Copyright 2025 Intelligent Robotics Lab
2//
3// This file is part of the project Easy Navigation (EasyNav in short)
4// licensed under the GNU General Public License v3.0.
5// See <http://www.gnu.org/licenses/> for details.
6//
7// Easy Navigation program is free software: you can redistribute it and/or modify
8// it under the terms of the GNU General Public License as published by
9// the Free Software Foundation, either version 3 of the License, or
10// (at your option) any later version.
11//
12// This program is distributed in the hope that it will be useful,
13// but WITHOUT ANY WARRANTY; without even the implied warranty of
14// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15// GNU General Public License for more details.
16//
17// You should have received a copy of the GNU General Public License
18// along with this program. If not, see <http://www.gnu.org/licenses/>.
19
26
27#ifndef EASYNAV_COMMON_TYPES__GNSSPERCEPTIONS_HPP_
28#define EASYNAV_COMMON_TYPES__GNSSPERCEPTIONS_HPP_
29
30#include <string>
31#include <vector>
32
33#include "sensor_msgs/msg/nav_sat_fix.hpp"
34
35#include "rclcpp_lifecycle/lifecycle_node.hpp"
36
38
39namespace easynav
40{
41
47{
48public:
50 static constexpr std::string_view default_group_ = "gnss";
51
55 static inline bool supports_msg_type(std::string_view t)
56 {
57 return t == "sensor_msgs/msg/NavSatFix";
58 }
59
61 sensor_msgs::msg::NavSatFix data;
62};
63
69{
70public:
73 std::string group() const override {return "gnss";}
74
78 std::shared_ptr<PerceptionBase> create(const std::string &) override
79 {
80 return std::make_shared<GNSSPerception>();
81 }
82
94 rclcpp::SubscriptionBase::SharedPtr create_subscription(
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;
100};
101
109 std::vector<std::shared_ptr<GNSSPerception>>;
110
114rclcpp::Time get_latest_gnss_perceptions_stamp(const GNSSPerceptions & perceptions);
115
116} // namespace easynav
117
118#endif // EASYNAV_COMMON_TYPES__GNSSPERCEPTIONS_HPP_
Defines data structures and utilities for representing and processing sensor perceptions.
Handles the creation and updating of GNSSPerception instances from sensor_msgs::msg::NavSatFix messag...
Definition GNSSPerception.hpp:69
std::shared_ptr< PerceptionBase > create(const std::string &) override
Creates a new empty GNSSPerception instance.
Definition GNSSPerception.hpp:78
std::string group() const override
Returns the group managed by this handler.
Definition GNSSPerception.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 GNSS topic that updates a target GNSSPerception.
Definition GNSSPerception.cpp:34
Represents a single GNSS perception from a sensor.
Definition GNSSPerception.hpp:47
sensor_msgs::msg::NavSatFix data
GNSS data received from the sensor.
Definition GNSSPerception.hpp:61
static bool supports_msg_type(std::string_view t)
Returns whether the given ROS 2 type name is supported by this perception.
Definition GNSSPerception.hpp:55
static constexpr std::string_view default_group_
Group identifier for GNSS perceptions.
Definition GNSSPerception.hpp:50
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
rclcpp::Time get_latest_gnss_perceptions_stamp(const GNSSPerceptions &perceptions)
Retrieves the latest timestamp among a set of GNSS perceptions.
Definition GNSSPerception.cpp:63
std::vector< std::shared_ptr< GNSSPerception > > GNSSPerceptions
Alias for a vector of shared pointers to GNSSPerception objects.
Definition GNSSPerception.hpp:108