ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Incorrect camera extrinsics for simulated Gazebo cameras

asked 2011-04-18 16:24:02 -0600

mkoval gravatar image

I am simulating several cameras in Gazebo using the gazebo_ros_camera plugin in the gazebo_plugins package. All of the cameras are defined in the robot's URDF and the corresponding coordinate frames are published by the joint_state_publisher and robot_state_publisher nodes.

When I view frames captured from the simulated cameras, it is clear that they are pointing in roughly the correct direction. If I view the simulated world in RViz, the visualized world renders correctly for horizontal cameras (left), but not for cameras with a non-zero pitch (right):

Image from Horizontal Camera Image from Angled Camera

It appears that the images captured in Gazebo have approximately twice the pitch that is specified in the URDF (note how the ground plane projected by RViz is too high in the right image). Has anyone else run into a similar problem?

edit retag flag offensive close merge delete

4 Answers

Sort by ยป oldest newest most voted
3

answered 2011-04-20 07:22:53 -0600

hsu gravatar image

Hi,

For pin hole cameras that gazebo is simulating, the equation below holds,

focal_lengtth = image_width / (2*tan(hfov_radian / 2)

One way to avoid inconsistency is to NOT specify <focal_length> tag in your XML. That way, <focal_length> is calculated using the above formula.

In addition, I'll patch gazebo_ros_camera plugin to raise an inconsistency error message when a focal_length is provided that is inconsistent with image_width and hfov.

Will that fix the problem for you?

Thanks, John

edit flag offensive delete link more

Comments

hi, if i want the focal_length value in mm or pixel dimensions (pixel per mm). i have already the intrinsic parameters from calibration. ( i am using gazebo )

leogeo gravatar image leogeo  ( 2020-10-02 05:03:26 -0600 )edit
1

answered 2011-04-19 09:40:51 -0600

mkoval gravatar image

I found the problem. In the PR2 sample code, there is a a comment above the focal_length element:

<!-- image_width / (2*tan(hfov_radian /2)) -->
<!-- 320 for wide and 772.55 for narrow stereo camera -->
<focal_length>320</focal_length>

I assumed that this was a PR2-specific comment and set focal_length to my camera's actual focal length. It turns out that always uses the value image_width / (2*tan(hfov_radian / 2), and only uses the value of focal_length for publishing camera_info. If focal_length is set to a different value, the focal length used by Gazebo will not match the focal length used by RViz. Making both focal lengths match fixed the rendering differences.

edit flag offensive delete link more
0

answered 2011-04-20 07:43:24 -0600

hsu gravatar image

Note that this won't fix the problem for you automatically as noted above... should I make the plugin overwrite the incorrect focal_length variable? I thought maybe some users might want the flexibility of specifying an incorrect focal length for testing purposes.

edit flag offensive delete link more

Comments

I can't think of a situation where specifying an invalid focal length would be useful for testing. Since Gazebo ignores this field, all nodes that use the published camera_info will give incorrect results. Adding a ROS_ERROR or ROS_WARNING sounds like a great solution. Thanks for your help!
mkoval gravatar image mkoval  ( 2011-04-20 16:32:55 -0600 )edit
0

answered 2011-04-20 07:41:43 -0600

hsu gravatar image

please see ticket with patch.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2011-04-18 16:24:02 -0600

Seen: 1,766 times

Last updated: Apr 20 '11