#include <camera_utilities.h>
| Public Member Functions | |
| 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::Vector2f | rectifiedAuxProject (const Eigen::Vector3f &left_rectified_point, const sensor_msgs::CameraInfo &aux_camera_info) 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... | |
| 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) 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... | |
| Private Attributes | |
| sensor_msgs::CameraInfo | aux_camera_info_ | 
| const crl::multisense::image::Calibration | calibration_ | 
| crl::multisense::image::Config | config_ | 
| const crl::multisense::system::DeviceInfo & | device_info_ | 
| sensor_msgs::CameraInfo | left_camera_info_ | 
| std::shared_ptr< RectificationRemapT > | left_remap_ | 
| std::mutex | mutex_ | 
| Eigen::Matrix4d | q_matrix_ | 
| sensor_msgs::CameraInfo | right_camera_info_ | 
| std::shared_ptr< RectificationRemapT > | right_remap_ | 
Definition at line 149 of file camera_utilities.h.
| multisense_ros::StereoCalibrationManager::StereoCalibrationManager | ( | const crl::multisense::image::Config & | config, | 
| const crl::multisense::image::Calibration & | calibration, | ||
| const crl::multisense::system::DeviceInfo & | device_info | ||
| ) | 
Definition at line 243 of file camera_utilities.cpp.
| 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.
| sensor_msgs::CameraInfo multisense_ros::StereoCalibrationManager::auxCameraInfo | ( | const std::string & | frame_id, | 
| const ros::Time & | stamp, | ||
| const OperatingResolutionT & | resolution | ||
| ) | const | 
Definition at line 461 of file camera_utilities.cpp.
| sensor_msgs::CameraInfo multisense_ros::StereoCalibrationManager::auxCameraInfo | ( | const std::string & | frame_id, | 
| const ros::Time & | stamp, | ||
| size_t | width, | ||
| size_t | height | ||
| ) | const | 
Definition at line 468 of file camera_utilities.cpp.
| crl::multisense::image::Config multisense_ros::StereoCalibrationManager::config | ( | ) | const | 
Definition at line 293 of file camera_utilities.cpp.
| sensor_msgs::CameraInfo multisense_ros::StereoCalibrationManager::leftCameraInfo | ( | const std::string & | frame_id, | 
| const ros::Time & | stamp | ||
| ) | const | 
Definition at line 438 of file camera_utilities.cpp.
| std::shared_ptr< RectificationRemapT > multisense_ros::StereoCalibrationManager::leftRemap | ( | ) | const | 
Definition at line 484 of file camera_utilities.cpp.
| OperatingResolutionT multisense_ros::StereoCalibrationManager::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.
Definition at line 412 of file camera_utilities.cpp.
| OperatingResolutionT multisense_ros::StereoCalibrationManager::operatingStereoResolution | ( | ) | const | 
Get the current main stereo pair operating resolution. This resolution applies for both the mono and rectified topics.
Definition at line 405 of file camera_utilities.cpp.
| Eigen::Matrix4d multisense_ros::StereoCalibrationManager::Q | ( | ) | const | 
Q stereo reprojection matrix see: https://docs.opencv.org/4.3.0/d9/d0c/group__calib3d.html#ga1bc1152bd57d63bc524204f21fde6e02.
Definition at line 300 of file camera_utilities.cpp.
| 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 377 of file camera_utilities.cpp.
| Eigen::Vector2f multisense_ros::StereoCalibrationManager::rectifiedAuxProject | ( | const Eigen::Vector3f & | left_rectified_point, | 
| const sensor_msgs::CameraInfo & | aux_camera_info | ||
| ) | const | 
Project points corresponding to disparity measurements in the left rectified image frame into the aux rectified image plane.
Definition at line 384 of file camera_utilities.cpp.
| Eigen::Vector3f multisense_ros::StereoCalibrationManager::reproject | ( | size_t | u, | 
| size_t | v, | ||
| double | d | ||
| ) | const | 
Reproject disparity values into 3D.
Definition at line 341 of file camera_utilities.cpp.
| 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 | ||
| ) | const | 
Reproject disparity values into 3D.
Definition at line 348 of file camera_utilities.cpp.
| sensor_msgs::CameraInfo multisense_ros::StereoCalibrationManager::rightCameraInfo | ( | const std::string & | frame_id, | 
| const ros::Time & | stamp | ||
| ) | const | 
Definition at line 450 of file camera_utilities.cpp.
| std::shared_ptr< RectificationRemapT > multisense_ros::StereoCalibrationManager::rightRemap | ( | ) | const | 
Definition at line 491 of file camera_utilities.cpp.
| 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.
| void multisense_ros::StereoCalibrationManager::updateConfig | ( | const crl::multisense::image::Config & | config | ) | 
Definition at line 259 of file camera_utilities.cpp.
| bool multisense_ros::StereoCalibrationManager::validAux | ( | ) | const | 
Determine if the Aux calibration is valid.
Definition at line 432 of file camera_utilities.cpp.
| bool multisense_ros::StereoCalibrationManager::validRight | ( | ) | const | 
Determine if the Right calibration is valid.
Definition at line 427 of file camera_utilities.cpp.
| 
 | private | 
Definition at line 260 of file camera_utilities.h.
| 
 | private | 
Definition at line 245 of file camera_utilities.h.
| 
 | private | 
Definition at line 244 of file camera_utilities.h.
| 
 | private | 
Definition at line 246 of file camera_utilities.h.
| 
 | private | 
Definition at line 258 of file camera_utilities.h.
| 
 | private | 
Definition at line 262 of file camera_utilities.h.
| 
 | mutableprivate | 
Definition at line 251 of file camera_utilities.h.
| 
 | private | 
Definition at line 256 of file camera_utilities.h.
| 
 | private | 
Definition at line 259 of file camera_utilities.h.
| 
 | private | 
Definition at line 263 of file camera_utilities.h.