fix: camera info width and height
This commit is contained in:
parent
65e7a4b288
commit
c81f51fdee
|
@ -1322,6 +1322,8 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
sensor_msgs::CameraInfo *camera_info = new sensor_msgs::CameraInfo();
|
sensor_msgs::CameraInfo *camera_info = new sensor_msgs::CameraInfo();
|
||||||
camera_info_ptrs_[stream] = sensor_msgs::CameraInfoPtr(camera_info);
|
camera_info_ptrs_[stream] = sensor_msgs::CameraInfoPtr(camera_info);
|
||||||
auto info_pair = api_->GetCameraROSMsgInfoPair();
|
auto info_pair = api_->GetCameraROSMsgInfoPair();
|
||||||
|
camera_info->width = info_pair->left.width;
|
||||||
|
camera_info->height = info_pair->left.height;
|
||||||
if (is_intrinsics_enable_) {
|
if (is_intrinsics_enable_) {
|
||||||
if (stream == Stream::RIGHT ||
|
if (stream == Stream::RIGHT ||
|
||||||
stream == Stream::RIGHT_RECTIFIED) {
|
stream == Stream::RIGHT_RECTIFIED) {
|
||||||
|
|
Loading…
Reference in New Issue
Block a user