|
Auterion App SDK
Auterion SDK is a library that can be used by AuterionOS apps to communicate with the system.
|
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)> |
| using | ImageFDCallback = std::function< void(const std::shared_ptr< ImageFD > &image_fd)> |
Public Member Functions | |
| Camera (SDK &sdk, const CameraDescriptor &camera_descriptor) | |
| void | subscribeImage (const ImageCallback &callback) |
| void | subscribeImageFD (const ImageFDCallback &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. | |
| std::optional< cv::Size > | getLastImageSize () const |
| Returns the size of the last received image, if available. | |
| Eigen::Vector3d | unprojectImagePoint (const cv::Point &image_point) const |
| Determine the (relative) camera-frame 3D position of a point in an image. | |
| 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. | |
| 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. | |
| bool | getDeltaRotationWorldCamera (Eigen::Quaterniond &q_delta_world_camera, tf2::TimePoint &time_start, tf2::TimePoint &time_end) |
| Calculates how much the camera has rotated between two points in time based only on gyro data. | |
| bool | getCameraInfo (sensor_msgs::msg::CameraInfo &camera_info) const |
| Get the camera information data for the camera. | |
| const CameraDescriptor & | descriptor () 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< Camera > | open (SDK &sdk, const std::string &unique_name, const std::chrono::seconds &timeout=30s) |
| static std::optional< Camera > | open (SDK &sdk, const std::function< bool(const CameraDescriptor &)> &find_callback, const std::chrono::seconds &timeout=30s) |
| static std::optional< Camera > | openFirst (SDK &sdk, const std::chrono::seconds &timeout=30s) |
Camera client to subscribe to a camera image stream.
| bool auterion::Camera::cameraInfoValid | ( | ) | const |
Determine whether a camera info message contains valid data.
| bool auterion::Camera::getCameraInfo | ( | sensor_msgs::msg::CameraInfo & | camera_info | ) | const |
Get the camera information data for the camera.
| camera_info | Camera information data. |
| bool auterion::Camera::getDeltaRotationWorldCamera | ( | Eigen::Quaterniond & | q_delta_world_camera, |
| tf2::TimePoint & | time_start, | ||
| tf2::TimePoint & | time_end | ||
| ) |
Calculates how much the camera has rotated between two points in time based only on gyro data.
This function computes the change in orientation of the camera's optical frame between time_start and time_end, using transforms from the TF2 buffer.
The result is a quaternion (q_delta_world_camera) that represents the rotation from the camera's orientation at time_start to its orientation at time_end, relative to the world (inertial) frame.
If a transform at the requested time is not available or is invalid (e.g., a zero quaternion), the function will fall back to the latest available valid transform. If a fallback is used, the time_start and time_end values will be updated to match the actual times of the data used.
| [out] | q_delta_world_camera | The computed relative rotation from start to end time, represented as a quaternion in the world frame. |
| [in,out] | time_start | The start time of the rotation interval. May be updated if fallback is used. |
| [in,out] | time_end | The end time of the rotation interval. May be updated if fallback is used. |
true if the rotation was successfully calculated, false if transform data was unavailable.time_start and time_end are the same, no rotation is assumed and the identity quaternion is returned. | std::optional< cv::Size > auterion::Camera::getLastImageSize | ( | ) | const |
Returns the size of the last received image, if available.
This is updated with every new image and can be used to determine the current image resolution.
| 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:
| q_body_camera | Rotation quaternion of the camera with respect to the body frame. |
| t_body_camera | Translation of the camera with respect to the body frame. |
| 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:
| q_enu_camera | Rotation quaternion of the camera with respect to the ENU world frame. |
| t_enu_camera | Translation of the camera with respect to the ENU world frame. |
| time | Optional parameter specifying the time point for which the pose is requested. Defaults to the earliest possible time. |
| void auterion::Camera::subscribeImage | ( | const ImageCallback & | callback | ) |
Subscribe to image updates. Note that the image is only valid for the duration of the callback.
| callback |
| Eigen::Vector3d auterion::Camera::unprojectImagePoint | ( | const cv::Point & | image_point | ) | const |
Determine the (relative) camera-frame 3D position of a point in an image.
| image_point | A 2D point in an image. |
|
static |
Setup camera to enable registering image callbacks