#include <camera_utilities.h>
|
Eigen::Vector3d | aux_T () const |
| Translation which transforms points from the rectified left camera frame into the rectified aux camera frame. More...
|
|
sensor_msgs::CameraInfo | auxCameraInfo (const std::string &frame_id, const ros::Time &stamp, const OperatingResolutionT &resolution) const |
|
sensor_msgs::CameraInfo | auxCameraInfo (const std::string &frame_id, const ros::Time &stamp, size_t width, size_t height) const |
|
crl::multisense::image::Config | config () const |
|
sensor_msgs::CameraInfo | leftCameraInfo (const std::string &frame_id, const ros::Time &stamp) const |
|
std::shared_ptr< RectificationRemapT > | leftRemap () const |
|
OperatingResolutionT | operatingAuxResolution () const |
| Get the current aux camera operating resolution. This resolution applies for just the mono topics. The Rectified aux topics match the operating stereo resolution. More...
|
|
OperatingResolutionT | operatingStereoResolution () const |
| Get the current main stereo pair operating resolution. This resolution applies for both the mono and rectified topics. More...
|
|
Eigen::Matrix4d | Q () const |
| Q stereo reprojection matrix see: https://docs.opencv.org/4.3.0/d9/d0c/group__calib3d.html#ga1bc1152bd57d63bc524204f21fde6e02. More...
|
|
Eigen::Vector2f | rectifiedAuxProject (const Eigen::Vector3f &left_rectified_point) const |
| Project points corresponding to disparity measurements in the left rectified image frame into the aux rectified image plane. More...
|
|
Eigen::Vector3f | reproject (size_t u, size_t v, double d) const |
| Reproject disparity values into 3D. More...
|
|
sensor_msgs::CameraInfo | rightCameraInfo (const std::string &frame_id, const ros::Time &stamp) const |
|
std::shared_ptr< RectificationRemapT > | rightRemap () const |
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | StereoCalibrationManager (const crl::multisense::image::Config &config, const crl::multisense::image::Calibration &calibration, const crl::multisense::system::DeviceInfo &device_info) |
|
double | T () const |
| Translation which transforms points from the rectified left camera frame into the recified right camera frame. More...
|
|
void | updateConfig (const crl::multisense::image::Config &config) |
|
bool | validAux () const |
| Determine if the Aux calibration is valid. More...
|
|
bool | validRight () const |
| Determine if the Right calibration is valid. More...
|
|
|
static bool | isValidReprojectedPoint (const Eigen::Vector3f &pt, const float squared_max_range) |
| Check if a reprojected point falls within a valid range. More...
|
|
static Eigen::Vector2f | rectifiedAuxProject (const Eigen::Vector3f &left_rectified_point, const sensor_msgs::CameraInfo &aux_camera_info) |
| Project points corresponding to disparity measurements in the left rectified image frame into the aux rectified image plane. More...
|
|
static Eigen::Vector3f | reproject (size_t u, size_t v, double d, const sensor_msgs::CameraInfo &left_camera_info, const sensor_msgs::CameraInfo &right_camera_info) |
| Reproject disparity values into 3D. More...
|
|
Definition at line 150 of file camera_utilities.h.
◆ StereoCalibrationManager()
◆ aux_T()
Eigen::Vector3d multisense_ros::StereoCalibrationManager::aux_T |
( |
| ) |
const |
Translation which transforms points from the rectified left camera frame into the rectified aux camera frame.
Definition at line 323 of file camera_utilities.cpp.
◆ auxCameraInfo() [1/2]
sensor_msgs::CameraInfo multisense_ros::StereoCalibrationManager::auxCameraInfo |
( |
const std::string & |
frame_id, |
|
|
const ros::Time & |
stamp, |
|
|
const OperatingResolutionT & |
resolution |
|
) |
| const |
◆ auxCameraInfo() [2/2]
sensor_msgs::CameraInfo multisense_ros::StereoCalibrationManager::auxCameraInfo |
( |
const std::string & |
frame_id, |
|
|
const ros::Time & |
stamp, |
|
|
size_t |
width, |
|
|
size_t |
height |
|
) |
| const |
◆ config()
◆ isValidReprojectedPoint()
bool multisense_ros::StereoCalibrationManager::isValidReprojectedPoint |
( |
const Eigen::Vector3f & |
pt, |
|
|
const float |
squared_max_range |
|
) |
| |
|
static |
◆ leftCameraInfo()
sensor_msgs::CameraInfo multisense_ros::StereoCalibrationManager::leftCameraInfo |
( |
const std::string & |
frame_id, |
|
|
const ros::Time & |
stamp |
|
) |
| const |
◆ leftRemap()
std::shared_ptr< RectificationRemapT > multisense_ros::StereoCalibrationManager::leftRemap |
( |
| ) |
const |
◆ operatingAuxResolution()
Get the current aux camera operating resolution. This resolution applies for just the mono topics. The Rectified aux topics match the operating stereo resolution.
Definition at line 417 of file camera_utilities.cpp.
◆ operatingStereoResolution()
Get the current main stereo pair operating resolution. This resolution applies for both the mono and rectified topics.
Definition at line 410 of file camera_utilities.cpp.
◆ Q()
Eigen::Matrix4d multisense_ros::StereoCalibrationManager::Q |
( |
| ) |
const |
◆ rectifiedAuxProject() [1/2]
Eigen::Vector2f multisense_ros::StereoCalibrationManager::rectifiedAuxProject |
( |
const Eigen::Vector3f & |
left_rectified_point | ) |
const |
Project points corresponding to disparity measurements in the left rectified image frame into the aux rectified image plane.
Definition at line 382 of file camera_utilities.cpp.
◆ rectifiedAuxProject() [2/2]
Eigen::Vector2f multisense_ros::StereoCalibrationManager::rectifiedAuxProject |
( |
const Eigen::Vector3f & |
left_rectified_point, |
|
|
const sensor_msgs::CameraInfo & |
aux_camera_info |
|
) |
| |
|
static |
Project points corresponding to disparity measurements in the left rectified image frame into the aux rectified image plane.
Definition at line 389 of file camera_utilities.cpp.
◆ reproject() [1/2]
Eigen::Vector3f multisense_ros::StereoCalibrationManager::reproject |
( |
size_t |
u, |
|
|
size_t |
v, |
|
|
double |
d |
|
) |
| const |
◆ reproject() [2/2]
Eigen::Vector3f multisense_ros::StereoCalibrationManager::reproject |
( |
size_t |
u, |
|
|
size_t |
v, |
|
|
double |
d, |
|
|
const sensor_msgs::CameraInfo & |
left_camera_info, |
|
|
const sensor_msgs::CameraInfo & |
right_camera_info |
|
) |
| |
|
static |
◆ rightCameraInfo()
sensor_msgs::CameraInfo multisense_ros::StereoCalibrationManager::rightCameraInfo |
( |
const std::string & |
frame_id, |
|
|
const ros::Time & |
stamp |
|
) |
| const |
◆ rightRemap()
std::shared_ptr< RectificationRemapT > multisense_ros::StereoCalibrationManager::rightRemap |
( |
| ) |
const |
◆ T()
double multisense_ros::StereoCalibrationManager::T |
( |
| ) |
const |
Translation which transforms points from the rectified left camera frame into the recified right camera frame.
Definition at line 307 of file camera_utilities.cpp.
◆ updateConfig()
◆ validAux()
bool multisense_ros::StereoCalibrationManager::validAux |
( |
| ) |
const |
◆ validRight()
bool multisense_ros::StereoCalibrationManager::validRight |
( |
| ) |
const |
◆ aux_camera_info_
sensor_msgs::CameraInfo multisense_ros::StereoCalibrationManager::aux_camera_info_ |
|
private |
◆ calibration_
◆ config_
◆ device_info_
◆ left_camera_info_
sensor_msgs::CameraInfo multisense_ros::StereoCalibrationManager::left_camera_info_ |
|
private |
◆ left_remap_
◆ mutex_
std::mutex multisense_ros::StereoCalibrationManager::mutex_ |
|
mutableprivate |
◆ q_matrix_
Eigen::Matrix4d multisense_ros::StereoCalibrationManager::q_matrix_ |
|
private |
◆ right_camera_info_
sensor_msgs::CameraInfo multisense_ros::StereoCalibrationManager::right_camera_info_ |
|
private |
◆ right_remap_
The documentation for this class was generated from the following files: