Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Non-zero Tx values with multiple cameras #487

Open
Tacha-S opened this issue Dec 11, 2024 · 1 comment
Open

Non-zero Tx values with multiple cameras #487

Tacha-S opened this issue Dec 11, 2024 · 1 comment
Labels
bug Something isn't working

Comments

@Tacha-S
Copy link

Tacha-S commented Dec 11, 2024

Environment

  • OS Version: Ubuntu 24.04
  • binary build version: 8.7.0

Description

  • Expected behavior:

Tx should be zero for all cameras.

  • Actual behavior:

When placing multiple cameras with different frames in Gz,
the Tx value of the second and subsequent cameras does not become zero,
even though they are ideal cameras without distortion.

Steps to reproduce

  1. Place two or more cameras in Gazebo, each assigned to a separate frame.
  2. Use gz topic -e to check the Tx values for each camera.

Output

camera info 1

gz topic -e -t /camera1/rgb/camera_info -n 1
header {
  stamp {
    sec: 506
    nsec: 90000000
  }
  data {
    key: "frame_id"
    value: "camera1_rgb_optical_frame"
  }
}
width: 640
height: 480
distortion {
  k: 0
  k: 0
  k: 0
  k: 0
  k: 0
}
intrinsics {
  k: 320
  k: 0
  k: 320
  k: 0
  k: 320.00000953674316
  k: 240
  k: 0
  k: 0
  k: 1
}
projection {
  p: 320
  p: 0
  p: 320
  p: 0
  p: 0
  p: 320.00000953674316
  p: 240
  p: 0
  p: 0
  p: 0
  p: 1
  p: 0
}
rectification_matrix: 1
rectification_matrix: 0
rectification_matrix: 0
rectification_matrix: 0
rectification_matrix: 1
rectification_matrix: 0
rectification_matrix: 0
rectification_matrix: 0
rectification_matrix: 1

camera info 2

gz topic -e -t /camera2/rgb/camera_info -n 1
header {
  stamp {
    sec: 609
    nsec: 120000000
  }
  data {
    key: "frame_id"
    value: "camera2_rgb_optical_frame"
  }
}
width: 1280
height: 720
distortion {
  k: 0
  k: 0
  k: 0
  k: 0
  k: 0
}
intrinsics {
  k: 1249.0565490722656
  k: 0
  k: 640
  k: 0
  k: 1249.0565013885498
  k: 360
  k: 0
  k: 0
  k: 1
}
projection {
  p: 1249.0565490722656
  p: 0
  p: 640
  p: -56.832072982788084  <------ Tx is not 0
  p: 0
  p: 1249.0565013885498
  p: 360
  p: 0
  p: 0
  p: 0
  p: 1
  p: 0
}
rectification_matrix: 1
rectification_matrix: 0
rectification_matrix: 0
rectification_matrix: 0
rectification_matrix: 1
rectification_matrix: 0
rectification_matrix: 0
rectification_matrix: 0
rectification_matrix: 1
@Tacha-S Tacha-S added the bug Something isn't working label Dec 11, 2024
@Tacha-S
Copy link
Author

Tacha-S commented Dec 11, 2024

I have confirmed that it is possible to set the baseline for the stereo camera, but is there a way to disable it?

void CameraSensor::SetBaseline(double _baseline)
{
this->dataPtr->baseline = _baseline;
// Also update message
if (this->dataPtr->infoMsg.has_projection() &&
this->dataPtr->infoMsg.projection().p_size() == 12)
{
auto fx = this->dataPtr->infoMsg.projection().p(0);
this->dataPtr->infoMsg.mutable_projection()->set_p(3, -fx * _baseline);
}
}

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
Status: Inbox
Development

No branches or pull requests

1 participant