Easy Navigation
Loading...
Searching...
No Matches
ImagePerception.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__IMAGEPERCEPTIONS_HPP_
28#define EASYNAV_COMMON_TYPES__IMAGEPERCEPTIONS_HPP_
29
30#include <string>
31#include <vector>
32#include <optional>
33
34#include "cv_bridge/cv_bridge.hpp"
35#include "sensor_msgs/msg/image.hpp"
36
37#include "rclcpp/time.hpp"
38#include "rclcpp_lifecycle/lifecycle_node.hpp"
39
41
42namespace easynav
43{
44
50{
51public:
53 cv::Mat data;
54};
55
62{
63public:
66 std::string group() const override {return "image";}
67
71 std::shared_ptr<PerceptionBase> create(const std::string &) override
72 {
73 return std::make_shared<ImagePerception>();
74 }
75
83 rclcpp::SubscriptionBase::SharedPtr create_subscription(
84 rclcpp_lifecycle::LifecycleNode & node,
85 const std::string & topic,
86 const std::string & type,
87 std::shared_ptr<PerceptionBase> target,
88 rclcpp::CallbackGroup::SharedPtr cb_group) override;
89};
90
96 std::vector<std::shared_ptr<ImagePerception>>;
97
98} // namespace easynav
99
100#endif // EASYNAV_COMMON_TYPES__IMAGEPERCEPTIONS_HPP_
Defines data structures and utilities for representing and processing sensor perceptions.
Handles the creation and updating of ImagePerception instances from sensor_msgs::msg::Image messages.
Definition ImagePerception.hpp:62
std::shared_ptr< PerceptionBase > create(const std::string &) override
Creates a new empty ImagePerception instance.
Definition ImagePerception.hpp:71
std::string group() const override
Returns the group name this handler manages ("image").
Definition ImagePerception.hpp:66
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 image topic that updates an perception.
Definition ImagePerception.cpp:38
Represents a single image perception from a sensor.
Definition ImagePerception.hpp:50
cv::Mat data
Image data received from the sensor.
Definition ImagePerception.hpp:53
Abstract base class for representing a single sensor perception.
Definition Perceptions.hpp:50
Abstract base interface for group-specific perception handlers.
Definition Perceptions.hpp:87
Definition RTTFBuffer.hpp:30
std::vector< std::shared_ptr< ImagePerception > > ImagePerceptions
Alias for a vector of shared pointers to ImagePerception objects.
Definition ImagePerception.hpp:95