ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
I faced the exact same issue while simulating a custom stereo camera in Gazebo.
This happens if you don't set the hackBaseline
parameter.
Following is the Gazebo plugin I had used:
<!-- SENSOR PLUGIN -->
<gazebo reference="left_stereo_camera">
<sensor type="multicamera" name="stereocamera">
<always_on>true</always_on>
<update_rate>10</update_rate>
<camera name="left">
<pose>0 0 0 0 0 0</pose>
<horizontal_fov>${radians(front_camera_horizontal_fov)}</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<camera name="right">
<pose>0 -${front_camera_baseline} 0 0 0 0</pose>
<horizontal_fov>${radians(front_camera_horizontal_fov)}</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<plugin name="stereo_camera_controller" filename="libgazebo_ros_multicamera.so">
<robotNamespace>/</robotNamespace>
<cameraName>stereocamera</cameraName>
<alwaysOn>true</alwaysOn>
<updateRate>10</updateRate>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>stereo_optical</frameName>
<hackBaseline>${front_camera_baseline}</hackBaseline>
<distortion_k1>0.0</distortion_k1>
<distortion_k2>0.0</distortion_k2>
<distortion_k3>0.0</distortion_k3>
<distortion_t1>0.0</distortion_t1>
<distortion_t2>0.0</distortion_t2>
</plugin>
</sensor>
</gazebo>
If hackBaseline
is set to 0.00
:
Here you can see the dot in RViz at the centre of the optical frame.
hackBaseline
is set to 0.06
:2 | No.2 Revision |
I faced the exact same issue while simulating a custom stereo camera in Gazebo.
This happens if you don't set the hackBaseline
parameter.
Following is the Gazebo plugin I had used:
<!-- SENSOR PLUGIN -->
<gazebo reference="left_stereo_camera">
<sensor type="multicamera" name="stereocamera">
<always_on>true</always_on>
<update_rate>10</update_rate>
<camera name="left">
<pose>0 0 0 0 0 0</pose>
<horizontal_fov>${radians(front_camera_horizontal_fov)}</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<camera name="right">
<pose>0 -${front_camera_baseline} 0 0 0 0</pose>
<horizontal_fov>${radians(front_camera_horizontal_fov)}</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<plugin name="stereo_camera_controller" filename="libgazebo_ros_multicamera.so">
<robotNamespace>/</robotNamespace>
<cameraName>stereocamera</cameraName>
<alwaysOn>true</alwaysOn>
<updateRate>10</updateRate>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>stereo_optical</frameName>
<hackBaseline>${front_camera_baseline}</hackBaseline>
<distortion_k1>0.0</distortion_k1>
<distortion_k2>0.0</distortion_k2>
<distortion_k3>0.0</distortion_k3>
<distortion_t1>0.0</distortion_t1>
<distortion_t2>0.0</distortion_t2>
</plugin>
</sensor>
</gazebo>
If hackBaseline
is set to 0.00
:
Here you can see the dot in RViz at the centre of the optical frame.
hackBaseline
is set to 0.06
:
Note: Please let me know if this solution doesn't work out for you. If in case it does, feel free to upvote my answer.
3 | No.3 Revision |
I faced the exact same issue while simulating a custom stereo camera in Gazebo.
This happens if you don't set the hackBaseline
parameter.
Following is the Gazebo plugin I had used:
<!-- SENSOR PLUGIN -->
<gazebo reference="left_stereo_camera">
<sensor type="multicamera" name="stereocamera">
<always_on>true</always_on>
<update_rate>10</update_rate>
<camera name="left">
<pose>0 0 0 0 0 0</pose>
<horizontal_fov>${radians(front_camera_horizontal_fov)}</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<camera name="right">
<pose>0 -${front_camera_baseline} 0 0 0 0</pose>
<horizontal_fov>${radians(front_camera_horizontal_fov)}</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<plugin name="stereo_camera_controller" filename="libgazebo_ros_multicamera.so">
<robotNamespace>/</robotNamespace>
<cameraName>stereocamera</cameraName>
<alwaysOn>true</alwaysOn>
<updateRate>10</updateRate>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>stereo_optical</frameName>
<hackBaseline>${front_camera_baseline}</hackBaseline>
<distortion_k1>0.0</distortion_k1>
<distortion_k2>0.0</distortion_k2>
<distortion_k3>0.0</distortion_k3>
<distortion_t1>0.0</distortion_t1>
<distortion_t2>0.0</distortion_t2>
</plugin>
</sensor>
</gazebo>
If hackBaseline
is set to 0.00
:
Here you can see the dot in RViz at the centre of the optical frame.frame.
hackBaseline
is set to 0.06
:
Note: Please let me know if this solution doesn't work out for you. If in case it does, feel free to upvote my answer.