Auterion App SDK
Auterion SDK is a library that can be used by AuterionOS apps to communicate with the system.
Loading...
Searching...
No Matches
common.hpp
1/****************************************************************************
2 *
3 * Copyright 2025 Auterion AG. All rights reserved.
4 *
5 * Redistribution and use in source and binary forms, with or without
6 * modification, are permitted provided that the following conditions are met:
7 *
8 * 1. Redistributions of source code must retain the above copyright notice, this
9 * list of conditions and the following disclaimer.
10 *
11 * 2. Redistributions in binary form must reproduce the above copyright notice,
12 * this list of conditions and the following disclaimer in the documentation
13 * and/or other materials provided with the distribution.
14 *
15 * 3. Neither the name of the copyright holder nor the names of its contributors
16 * may be used to endorse or promote products derived from this software without
17 * specific prior written permission.
18 *
19 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 * POSSIBILITY OF SUCH DAMAGE.
30 *
31 ****************************************************************************/
32
33#pragma once
34
35#include <Eigen/Dense>
36#include <opencv2/core/mat.hpp>
37#include <opencv2/core/types.hpp>
38#include <optional>
39#include <rclcpp/rclcpp.hpp>
40
41namespace auterion {
47 UNKNOWN = 0, // Used for constructors and error handling
48 INACTIVE = 1, // No tracking is active
49 TRACKING = 2, // Actively tracking a target with good confidence
50 DEGRADED = 3, // Tracking with reduced confidence
51 LOST = 4 // Target was being tracked but has been lost
52};
53
59std::ostream& operator<<(std::ostream& os, const TrackingState& state);
60
67enum TrackingAdjustment {
68 NONE = 0,
69 ADJUST_DOWN = 1,
70 ADJUST_UP = 2,
71 ADJUST_LEFT = 3,
72 ADJUST_RIGHT = 4
73};
74
78std::ostream& operator<<(std::ostream& os, const TrackingAdjustment& adjustment);
79
85 public:
86 enum class Frame {
87 Camera,
88 Body, // equal to FMU
89 FMU, // equal to Body
90 World, // equal to ENU
91 ENU // equal to World
92 };
93
94 TrackingResult(const cv::Point& object_center, const cv::Size& object_size,
95 const float confidence = 1.f, TrackingState state = TrackingState::UNKNOWN);
96
98
99 TrackingResult& withConfidence(const float confidence);
100
101 TrackingResult& withObjectDirection(const Eigen::Vector3f& direction, Frame frame);
102
103 inline cv::Point getObjectCenter() const { return _object_center; }
104 inline cv::Size getObjectSize() const { return _object_size; }
105 inline float getConfidence() const { return _confidence; }
106 inline TrackingState getTrackingState() const { return _tracking_state; }
107 Eigen::Vector3f getObjectDirection(Frame frame = Frame::Camera) const;
108
109 private:
110 cv::Size _object_size;
111 cv::Point _object_center;
112 Eigen::Vector3f _object_direction_camera_frame;
114 Eigen::Vector3f _object_direction_body_frame;
116 Eigen::Vector3f _object_direction_world_frame;
118 float _confidence;
120 _tracking_state;
121};
122
134 cv::Point2d normalized_point;
138 std::optional<uint16_t> frame_id;
139
146 TrackingSelection(cv::Point2d normalized_point, std::optional<uint16_t> frame_id = std::nullopt)
148
163};
164} // namespace auterion
Camera client to subscribe to a camera image stream.
Definition camera.hpp:416
Represents the result of an image tracking operation.
Definition common.hpp:84
TrackingState
Tracking state enum to represent different tracking states.
Definition common.hpp:46
Represents the tracking selection as received by AMC.
Definition common.hpp:133
std::optional< uint16_t > frame_id
Optional identifier of the selected frame.
Definition common.hpp:138
TrackingSelection(cv::Point2d normalized_point, std::optional< uint16_t > frame_id=std::nullopt)
Constructor for creating a tracking selection with a point only.
Definition common.hpp:146
cv::Size2d normalized_window_size
Definition common.hpp:136
cv::Point2d normalized_point
Definition common.hpp:134
TrackingSelection(cv::Point2d normalized_point, cv::Size2d normalized_window_size, std::optional< uint16_t > frame_id=std::nullopt)
Constructor for creating a tracking selection with a point and a window size. This should be used whe...
Definition common.hpp:158