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

How to change Gazebo GUI focal length/FOV

asked 2012-01-16 15:41:28 -0500

Paul Vernaza gravatar image

Is it possible to change the focal length/field of view of the camera used to render the Gazebo GUI? The default focal length looks really short, which has the tragic effect of making my planning scenario look easy to reviewers :( I've noticed there is a camera tag in the world file, but it doesn't seem to be documented anywhere.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
4

answered 2012-01-17 19:07:07 -0500

Markus Bader gravatar image

updated 2012-01-17 19:12:38 -0500

Hello Paul!

Somewhere within the gazebo robot configuration you will find the camera parameters like the following: Changing the hfov will change you the field of view :-)

<sensor:camera name="cam_front_sensor">
  <imageSize>640 480</imageSize>
  <imageFormat>B8G8R8</imageFormat>
  <hfov>90</hfov>
  <nearClip>0.1</nearClip>
  <farClip>100</farClip>
  <updateRate>20.0</updateRate>
  .....
</sensor:camera>

You can compute the focal length with

f = (width/2) / tan( deg2rad(hfov)/2) = (640/2) / tan(deg2rad(90)/2) = 320

The example above will give you a focal length of 320. Don't forget to convert the angle to radiant

Greetings Markus Gazebo camera FOV vs. focal length

edit flag offensive delete link more
2

answered 2012-01-18 05:09:37 -0500

hsu gravatar image

Unfortunately, the camera used for rendering the gui does not have an easy way to change its FOV.

Ticketed feature request needs to be released.

Alternatively, you can create a static camera model in the world and set its fov as Markus described, and screen capture the images separately using image_view or rviz.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2012-01-16 15:41:28 -0500

Seen: 6,948 times

Last updated: Jan 18 '12