Auterion App SDK
Auterion SDK is a library that can be used by AuterionOS apps to communicate with the system.
auterion::TrackingInterface Class Reference

Provides an API to react to tracking related events, and update the current tracking status. More...

#include <auterion_sdk/tracking/tracking_interface.hpp>

Public Types

enum  TrackingKeyControl {
  NONE = 0 , ADJUST_DOWN = 1 , ADJUST_UP = 2 , ADJUST_LEFT = 3 ,
  ADJUST_RIGHT = 4
}
 Enum representing the control commands for tracking adjustments. More...
 
using ImageCallback = std::function< void(const auterion::Image &image)>
 
using CameraInfoCallback = std::function< void(const sensor_msgs::msg::CameraInfo::SharedPtr &camera_info)>
 
using TrackSelectionCallback = std::function< void(const TrackingSelection &selection)>
 
using TrackStopCallback = std::function< void(void)>
 
using TrackZoomChangeCallback = std::function< void(const int change)>
 
using TrackKeyControlCallback = std::function< void(const TrackingKeyControl key)>
 

Public Member Functions

 TrackingInterface (auterion::SDK &sdk, std::shared_ptr< auterion::Camera > camera=nullptr)
 Constructor that accepts a camera object. More...
 
 TrackingInterface (auterion::SDK &sdk, std::optional< auterion::CameraDescriptor > camera_descriptor)
 [Deprecated] Constructor that selects a camera based on a provided descriptor. More...
 
void subscribeImage (const ImageCallback &callback)
 Subscribes to incoming images. More...
 
void subscribeCameraInfo (const CameraInfoCallback &callback)
 Subscribes to camera information data. More...
 
void subscribeTrackingSelection (const TrackSelectionCallback &callback)
 Subscribes to tracking selection requests. More...
 
void subscribeTrackingOff (const TrackStopCallback &callback)
 Subscribes to the tracking off events. More...
 
void subscribeTrackingZoomChange (const TrackZoomChangeCallback &callback)
 Subscribes to the tracking zoom change events. More...
 
void subscribeKeyControl (const TrackKeyControlCallback &callback)
 Subscribes to the tracking key control events. More...
 
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 rendered by the receiving system. More...
 
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 rendered by the receiving system. More...
 
void updateResult (TrackingResult &tracking_result) const
 Updates the tracking result for connected systems. More...
 
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. More...
 

Detailed Description

Provides an API to react to tracking related events, and update the current tracking status.

Member Enumeration Documentation

◆ TrackingKeyControl

Enum representing the control commands for tracking adjustments.

This enum defines the possible commands that can be used to adjust the tracking direction.

Enumerator
NONE 

Not set.

ADJUST_DOWN 

Move down.

ADJUST_UP 

Move up.

ADJUST_LEFT 

Move left.

ADJUST_RIGHT 

Move right.

Constructor & Destructor Documentation

◆ TrackingInterface() [1/2]

auterion::TrackingInterface::TrackingInterface ( auterion::SDK sdk,
std::shared_ptr< auterion::Camera camera = nullptr 
)

Constructor that accepts a camera object.

Use this constructor to manually pass a camera object. Callbacks to camera data must be registered using the auterion::Camera object.

Parameters
sdkReference to the auterion::SDK instance.
cameraShared pointer to a camera object. If not provided, defaults to nullptr.

◆ TrackingInterface() [2/2]

auterion::TrackingInterface::TrackingInterface ( auterion::SDK sdk,
std::optional< auterion::CameraDescriptor camera_descriptor 
)

[Deprecated] Constructor that selects a camera based on a provided descriptor.

Use this constructor to automatically find a camera based on the provided (or default) descriptor. Callbacks to camera data must be registered using the auterion::TrackingInterface object.

Parameters
sdkReference to the auterion::SDK instance.
camera_descriptor[Optional] Descriptor used to find the camera. If not provided, the first available camera is selected.

Member Function Documentation

◆ getPoseBodyCamera()

bool auterion::TrackingInterface::getPoseBodyCamera ( Eigen::Vector3d &  t_body_camera,
Eigen::Quaterniond &  q_body_camera 
) const

Get the pose of the camera with respect to the body frame.

This function retrieves the pose of the camera relative to the body frame / FMU of the vehicle. The pose is represented by a rotation quaternion and a translation vector. ROS2 coordinate frame conventions are followed. Specifically:

  • The body frame is defined FLU (front=x, left=y,up=z).
  • The quaternion represents the orientation of the camera frame w.r.t. the body frame.
  • The translation represents the position of the camera frame w.r.t. the body frame.
Parameters
t_body_cameraTranslation of the camera with respect to the body frame.
q_body_cameraRotation quaternion of the camera with respect to the body frame.
Returns
true if the pose is successfully retrieved, false otherwise.

◆ subscribeCameraInfo()

void auterion::TrackingInterface::subscribeCameraInfo ( const CameraInfoCallback &  callback)

Subscribes to camera information data.

Parameters
callbackA callback function that will be called with the incoming camera information.

◆ subscribeImage()

void auterion::TrackingInterface::subscribeImage ( const ImageCallback &  callback)

Subscribes to incoming images.

Parameters
callbackA callback function that will be called with the incoming image.

◆ subscribeKeyControl()

void auterion::TrackingInterface::subscribeKeyControl ( const TrackKeyControlCallback &  callback)

Subscribes to the tracking key control events.

Parameters
callbackA callback function that will be called when the user uses the arrows to move the tracked point.

◆ subscribeTrackingOff()

void auterion::TrackingInterface::subscribeTrackingOff ( const TrackStopCallback &  callback)

Subscribes to the tracking off events.

Parameters
callbackA callback function that will be called when tracking is disabled.

◆ subscribeTrackingSelection()

void auterion::TrackingInterface::subscribeTrackingSelection ( const TrackSelectionCallback &  callback)

Subscribes to tracking selection requests.

Parameters
callbackA callback function that will be called with the tracking selection.

◆ subscribeTrackingZoomChange()

void auterion::TrackingInterface::subscribeTrackingZoomChange ( const TrackZoomChangeCallback &  callback)

Subscribes to the tracking zoom change events.

Parameters
callbackA callback function that will be called with the change of zoom level (int).

◆ updateImage() [1/2]

void auterion::TrackingInterface::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 rendered by the receiving system.

Parameters
imageThe image to display.
encodingThe encoding of the image.
displayed_region(optional) The region of the original image visible in the displayed image.
tracking_result(optional) The tracking result containing the new tracking data.

◆ updateImage() [2/2]

void auterion::TrackingInterface::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 rendered by the receiving system.

This overload assumes the displayed region is the full image.

Parameters
imageThe image to display.
encodingThe encoding of the image.
tracking_resultThe tracking result containing the new tracking data.

◆ updateResult()

void auterion::TrackingInterface::updateResult ( TrackingResult tracking_result) const

Updates the tracking result for connected systems.

Parameters
tracking_resultThe tracking result containing the new tracking data.

The documentation for this class was generated from the following file: