35 #include <Eigen/Eigen>
36 #include <auterion_sdk/auterion.hpp>
37 #include <auterion_sdk/camera/camera.hpp>
38 #include <opencv2/core/mat.hpp>
39 #include <opencv2/core/types.hpp>
61 TrackingResult(
const cv::Point& object_center,
const cv::Size& object_size,
62 const float confidence = 1.f);
67 TrackingResult& withObjectDirection(
const Eigen::Vector3f& direction, Frame frame);
69 inline cv::Point getObjectCenter()
const {
return _object_center; }
70 inline cv::Size getObjectSize()
const {
return _object_size; }
71 inline float getConfidence()
const {
return _confidence; }
72 Eigen::Vector3f getObjectDirection(Frame frame = Frame::Camera)
const;
75 cv::Size _object_size;
76 cv::Point _object_center;
77 Eigen::Vector3f _object_direction_camera_frame;
79 Eigen::Vector3f _object_direction_body_frame;
81 Eigen::Vector3f _object_direction_world_frame;
101 std::optional<rclcpp::Time>
128 class TrackingInterfaceImpl;
151 using ImageCallback = std::function<void(
const auterion::Image& image)>;
152 using CameraInfoCallback =
153 std::function<void(
const sensor_msgs::msg::CameraInfo::SharedPtr& camera_info)>;
154 using TrackSelectionCallback = std::function<void(
const TrackingSelection& selection)>;
155 using TrackStopCallback = std::function<void(
void)>;
156 using TrackZoomChangeCallback = std::function<void(
const int change)>;
182 "'camera_descriptor' not used anymore. This will be removed in some later "
184 std::optional<auterion::CameraDescriptor>
194 "Replace by equal function in camera interface. This will be removed in some later "
203 "Replace by equal function in camera interface. This will be removed in some later "
242 const std::optional<cv::Rect>& displayed_region = std::nullopt,
243 const std::optional<TrackingResult>& tracking_result = std::nullopt);
280 "Replace by equal function in camera interface. This will be removed in some later "
285 std::shared_ptr<TrackingInterfaceImpl> _impl;
Camera client to subscribe to a camera image stream.
Definition: camera.hpp:307
Contains image data with a specific encoding.
Definition: camera.hpp:202
SDK execution class. All callbacks are called on the same thread.
Definition: auterion.hpp:45
Provides an API to react to tracking related events, and update the current tracking status.
Definition: tracking_interface.hpp:135
void subscribeKeyControl(const TrackKeyControlCallback &callback)
Subscribes to the tracking key control events.
bool getPoseBodyCamera(Eigen::Vector3d &t_body_camera, Eigen::Quaterniond &q_body_camera) const
Get the pose of the camera with respect to the body frame.
void subscribeImage(const ImageCallback &callback)
Subscribes to incoming images.
void subscribeCameraInfo(const CameraInfoCallback &callback)
Subscribes to camera information data.
void subscribeTrackingZoomChange(const TrackZoomChangeCallback &callback)
Subscribes to the tracking zoom change events.
void updateImage(const cv::Mat &image, const auterion::ImageHeader::Encoding &encoding, const std::optional< cv::Rect > &displayed_region=std::nullopt, const std::optional< TrackingResult > &tracking_result=std::nullopt)
Updates image for connected systems to display and publishes the tracking result over MAVLink to be r...
void subscribeTrackingOff(const TrackStopCallback &callback)
Subscribes to the tracking off events.
TrackingInterface(auterion::SDK &sdk, std::optional< auterion::CameraDescriptor > camera_descriptor)
[Deprecated] Constructor that selects a camera based on a provided descriptor.
TrackingInterface(auterion::SDK &sdk, std::shared_ptr< auterion::Camera > camera=nullptr)
Constructor that accepts a camera object.
TrackingKeyControl
Enum representing the control commands for tracking adjustments.
Definition: tracking_interface.hpp:143
@ NONE
Not set.
Definition: tracking_interface.hpp:144
@ ADJUST_RIGHT
Move right.
Definition: tracking_interface.hpp:148
@ ADJUST_UP
Move up.
Definition: tracking_interface.hpp:146
@ ADJUST_DOWN
Move down.
Definition: tracking_interface.hpp:145
@ ADJUST_LEFT
Move left.
Definition: tracking_interface.hpp:147
void subscribeTrackingSelection(const TrackSelectionCallback &callback)
Subscribes to tracking selection requests.
void updateResult(TrackingResult &tracking_result) const
Updates the tracking result for connected systems.
void updateImage(const cv::Mat &image, const auterion::ImageHeader::Encoding &encoding, const TrackingResult &tracking_result)
Updates image for connected systems to display and publishes the tracking result over MAVLink to be r...
Represents the result of an image tracking operation.
Definition: tracking_interface.hpp:51
Represents the tracking selection as received by AMC.
Definition: tracking_interface.hpp:96
std::optional< rclcpp::Time > timestamp
Optional timestamp for the tracking selection (not currently used).
Definition: tracking_interface.hpp:102
cv::Size2d normalized_window_size
Definition: tracking_interface.hpp:99
TrackingSelection(cv::Point2d normalized_point)
Constructor for creating a tracking selection with a point only.
Definition: tracking_interface.hpp:109
cv::Point2d normalized_point
Definition: tracking_interface.hpp:97
TrackingSelection(cv::Point2d normalized_point, cv::Size2d normalized_window_size)
Constructor for creating a tracking selection with a point and a window size. This should be used whe...
Definition: tracking_interface.hpp:122