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

Camera client to subscribe to a camera image stream. More...

#include <auterion_sdk/camera/camera.hpp>

Public Types

using ImageCallback = std::function< void(const Image &image)>
 

Public Member Functions

 Camera (SDK &sdk, const CameraDescriptor &camera_descriptor)
 
void subscribeImage (const ImageCallback &callback)
 
void subscribeCameraInfo (std::function< void(const sensor_msgs::msg::CameraInfo::SharedPtr)> callback)
 
bool cameraInfoValid () const
 Determine whether a camera info message contains valid data. More...
 
std::optional< cv::Size > getLastImageSize () const
 Returns the last image size based on the camera image message. More...
 
Eigen::Vector3d unprojectImagePoint (const cv::Point &image_point) const
 Determine the (relative) camera-frame 3D position of a point in an image. More...
 
bool getPoseBodyCamera (Eigen::Quaterniond &q_body_camera, Eigen::Vector3d &t_body_camera) const
 Get the pose of the camera with respect to the body frame. More...
 
bool getPoseWorldCamera (Eigen::Quaterniond &q_enu_camera, Eigen::Vector3d &t_enu_camera, const tf2::TimePoint &time=tf2::TimePointZero) const
 Get the pose of the camera with respect to the ENU world frame. More...
 
bool getCameraInfo (sensor_msgs::msg::CameraInfo &camera_info) const
 Get the camera information data for the camera. More...
 
const CameraDescriptordescriptor () const
 

Static Public Member Functions

static Camera waitForCamera (SDK &sdk, const std::function< bool(const CameraDescriptor &)> &find_callback)
 
static Camera waitForCamera (SDK &sdk, std::optional< auterion::CameraDescriptor > camera_descriptor=std::nullopt)
 
static std::optional< Cameraopen (SDK &sdk, const std::string &unique_name, const std::chrono::seconds &timeout=30s)
 
static std::optional< Cameraopen (SDK &sdk, const std::function< bool(const CameraDescriptor &)> &find_callback, const std::chrono::seconds &timeout=30s)
 
static std::optional< CameraopenFirst (SDK &sdk, const std::chrono::seconds &timeout=30s)
 

Detailed Description

Camera client to subscribe to a camera image stream.

Member Function Documentation

◆ cameraInfoValid()

bool auterion::Camera::cameraInfoValid ( ) const

Determine whether a camera info message contains valid data.

Returns
True if valid distortion and intrinsic matrices are present and image size is non-zero.

◆ getCameraInfo()

bool auterion::Camera::getCameraInfo ( sensor_msgs::msg::CameraInfo &  camera_info) const

Get the camera information data for the camera.

Parameters
camera_infoCamera information data.
Returns
true if the camera info is successfully retrieved, false otherwise.

◆ getLastImageSize()

std::optional<cv::Size> auterion::Camera::getLastImageSize ( ) const

Returns the last image size based on the camera image message.

Returns
image size.

◆ getPoseBodyCamera()

bool auterion::Camera::getPoseBodyCamera ( Eigen::Quaterniond &  q_body_camera,
Eigen::Vector3d &  t_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
q_body_cameraRotation quaternion of the camera with respect to the body frame.
t_body_cameraTranslation of the camera with respect to the body frame.
Returns
true if the pose is successfully retrieved, false otherwise.

◆ getPoseWorldCamera()

bool auterion::Camera::getPoseWorldCamera ( Eigen::Quaterniond &  q_enu_camera,
Eigen::Vector3d &  t_enu_camera,
const tf2::TimePoint &  time = tf2::TimePointZero 
) const

Get the pose of the camera with respect to the ENU world frame.

This function retrieves the pose of the camera relative to the world frame (ENU convention). The pose is represented by a rotation quaternion and a translation vector. ROS2 coordinate frame conventions are followed. Specifically:

  • The world frame is defined ENU.
  • The rotation represents the orientation of the camera frame with respect to the ENU world frame.
  • The translation represents the position of the camera frame with respect to the ENU world frame.
Parameters
q_enu_cameraRotation quaternion of the camera with respect to the ENU world frame.
t_enu_cameraTranslation of the camera with respect to the ENU world frame.
timeOptional parameter specifying the time point for which the pose is requested. Defaults to the earliest possible time.
Returns
true if the pose is successfully retrieved, false otherwise.

◆ subscribeImage()

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

Subscribe to image updates. Note that the image is only valid for the duration of the callback.

Parameters
callback

◆ unprojectImagePoint()

Eigen::Vector3d auterion::Camera::unprojectImagePoint ( const cv::Point &  image_point) const

Determine the (relative) camera-frame 3D position of a point in an image.

Parameters
image_pointA 2D point in an image.
Returns
A 3D point describing the input pixel coordinates in the camera frame (normalize such that z=1.0).

◆ waitForCamera()

static Camera auterion::Camera::waitForCamera ( SDK sdk,
const std::function< bool(const CameraDescriptor &)> &  find_callback 
)
static

Setup camera to enable registering image callbacks


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