35 #include <Eigen/Eigen>
36 #include <auterion_sdk/auterion.hpp>
37 #include <auterion_sdk/camera/camera.hpp>
38 #include <auterion_sdk/tracking/common.hpp>
39 #include <opencv2/core/mat.hpp>
40 #include <opencv2/core/types.hpp>
48 class TrackingInterfaceImpl;
57 using ImageCallback = std::function<void(
const auterion::Image& image)>;
58 using CameraInfoCallback =
59 std::function<void(
const sensor_msgs::msg::CameraInfo::SharedPtr& camera_info)>;
60 using TrackSelectionCallback = std::function<void(
const TrackingSelection& selection)>;
61 using TrackStopCallback = std::function<void(
void)>;
62 using TrackZoomChangeCallback = std::function<void(
const int change)>;
63 using TrackAdjustmentCallback = std::function<void(
const TrackingAdjustment& adjustment)>;
66 using TrackingKeyControl
67 [[deprecated(
"TrackingKeyControl has been renamed. Please use TrackingAdjustment.")]] =
69 using TrackKeyControlCallback [[deprecated(
70 "TrackKeyControlCallback has been renamed. Please use TrackAdjustmentCallback.")]] =
71 TrackAdjustmentCallback;
96 "'camera_descriptor' not used anymore. This will be removed in some later "
98 std::optional<auterion::CameraDescriptor>
108 "Replace by equal function in camera interface. This will be removed in some later "
117 "Replace by equal function in camera interface. This will be removed in some later "
147 "subscribeKeyControl has been renamed. Please use subscribeTrackingAdjustment.")]]
void
148 subscribeKeyControl(
const TrackKeyControlCallback& callback) {
162 const std::optional<cv::Rect>& displayed_region = std::nullopt,
163 const std::optional<TrackingResult>& tracking_result = std::nullopt);
200 "Replace by equal function in camera interface. This will be removed in some later "
205 std::shared_ptr<TrackingInterfaceImpl> _impl;
Contains image data with a specific encoding.
Definition: camera.hpp:213
SDK execution class. All callbacks are called on the same thread.
Definition: auterion.hpp:97
Provides an API to react to tracking related events, and update the current tracking status.
Definition: tracking_interface.hpp:55
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.
void subscribeTrackingAdjustment(const TrackAdjustmentCallback &callback)
Subscribes to the tracking adjustment 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.
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: common.hpp:84
Represents the tracking selection as received by AMC.
Definition: common.hpp:133