-
Notifications
You must be signed in to change notification settings - Fork 59
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
Comments
I have confirmed that it is possible to set the baseline for the stereo camera, but is there a way to disable it? gz-sensors/src/CameraSensor.cc Lines 738 to 749 in aaef365
|
You should be able to add multiple |
Indeed, up to two cameras function correctly. However, starting from the third camera, it seems they do not behave as intended. <?xml version="1.0" encoding="UTF-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="bot">
<link name="link1">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder radius="0.1" length="0.2"/>
</geometry>
<material name="Black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.1"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1"/>
</inertial>
</link>
<gazebo reference="link1">
<sensor name="camera1" type="camera">
<always_on>true</always_on>
<update_rate>15.0</update_rate>
<topic>camera1/rgb/image_raw</topic>
<gz_frame_id>camera1_rgb_optical_frame</gz_frame_id>
<camera>
<camera_info_topic>camera1/rgb/camera_info</camera_info_topic>
<image>
<format>B8G8R8</format>
<width>640</width>
<height>480</height>
</image>
</camera>
</sensor>
</gazebo>
<joint name="camera_joint" type="fixed">
<origin xyz="2 0 0" rpy="0 0 0"/>
<parent link="link1"/>
<child link="link2"/>
</joint>
<link name="link2">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder radius="0.1" length="0.2"/>
</geometry>
<material name="Black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.1"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1"/>
</inertial>
</link>
<gazebo reference="link2">
<sensor name="camera2" type="camera">
<always_on>true</always_on>
<update_rate>15.0</update_rate>
<topic>camera2/rgb/image_raw</topic>
<gz_frame_id>camera2_rgb_optical_frame</gz_frame_id>
<camera>
<camera_info_topic>camera2/rgb/camera_info</camera_info_topic>
<image>
<format>B8G8R8</format>
<width>640</width>
<height>480</height>
</image>
</camera>
</sensor>
</gazebo>
<joint name="camera_joint2" type="fixed">
<origin xyz="0 2 0" rpy="0 0 0"/>
<parent link="link2"/>
<child link="link3"/>
</joint>
<link name="link3">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder radius="0.1" length="0.2"/>
</geometry>
<material name="Black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.1"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1"/>
</inertial>
</link>
<gazebo reference="link3">
<sensor name="camera3" type="camera">
<always_on>true</always_on>
<update_rate>15.0</update_rate>
<topic>camera3/rgb/image_raw</topic>
<gz_frame_id>camera3_rgb_optical_frame</gz_frame_id>
<camera>
<camera_info_topic>camera3/rgb/camera_info</camera_info_topic>
<image>
<format>B8G8R8</format>
<width>640</width>
<height>480</height>
</image>
</camera>
</sensor>
</gazebo>
<gazebo>
<plugin name="gz::sim::systems::Sensors" filename="gz-sim-sensors-system">
<render_engine>ogre2</render_engine>
</plugin>
</gazebo>
</robot> gz topic -e -t /camera3/rgb/camera_info
...
projection {
p: 554.38270568847656
p: 0
p: 320
p: -1108.7654113769531
p: 0
p: 554.38270568847656
p: 240
p: 0
p: 0
p: 0
p: 1
p: 0
}
... |
If there is a change in the Y direction of the link, Tx will not be zero, even with more than three cameras. This is likely because, even if different cameras are placed on separate links of the robot, if those links are connected by fixed joints, gz sim treats them as a single link. As a result, the baseline is applied to other cameras as well. |
Environment
Description
Tx
should be zero for all cameras.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
gz topic -e
to check the Tx values for each camera.Output
camera info 1
camera info 2
The text was updated successfully, but these errors were encountered: