ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
You can get the intrinsics by subscribing to the /camera_info
topic defined in the plugin:
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
The sensor_msgs/CameraInfo message will contain the camera matrix:
# Intrinsic camera matrix for the raw (distorted) images. # [fx 0 cx] # K = [ 0 fy cy] # [ 0 0 1] # Projects 3D points in the camera coordinate frame to 2D pixel # coordinates using the focal lengths (fx, fy) and principal point # (cx, cy). float64[9] K # 3x3 row-major matrix
Also, you can explicitly set the intrinsics in Gazebo as indicated in the camera SDF specification:
2 | No.2 Revision |
You can get the intrinsics by subscribing to the /camera_info
topic defined in the plugin:
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
The sensor_msgs/CameraInfo message will contain the camera matrix:
# Intrinsic camera matrix for the raw (distorted) images. # [fx 0 cx] # K = [ 0 fy cy] # [ 0 0 1] # Projects 3D points in the camera coordinate frame to 2D pixel # coordinates using the focal lengths (fx, fy) and principal point # (cx, cy). float64[9] K # 3x3 row-major matrix
Also, you can explicitly set the intrinsics in Gazebo as indicated in the camera SDF specification:
Note the ROS plugin and Gazebo sensor use two separate intrinsic parameter sets, so it's on the user to make sure they are correct. The ROS plugin source code shows how it uses the parameters only to fill the camera info. Here's an exampe:
<sensor type="camera" name="camera">
<update_rate>30.0</update_rate>
<camera name="head">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
<lens>
<intrinsics>
<fx>100</fx>
<fy>100</fy>
<cx>640</cx>
<cy>360</cy>
<s>0</s>
</intrinsics>
</lens>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>rrbot/camera1</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</frameName>
<Cx>640</Cx>
<Cy>360</Cy>
<focalLength>100</focalLength>
</plugin>
</sensor>