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

gazebo camera frame is inconsistent with rviz + opencv convention

asked 2016-04-21 13:23:37 -0500

lucasw gravatar image

updated 2020-11-21 11:20:59 -0500

It looks like the gazebo camera frame convention is not the same as rviz and opencv, which the image below shows

image description

In opencv, z is pointing into the image (the blue axis), x is right (the red axis), and y is down (green axis), while in the gazebo camera x is pointing into the image and z is up, y is right which is similar to the robot convention of x being forward and z up.

The image above is using an rviz/Camera to overlay the purple grid on the frame generated from the gazebo camera plugin, instead of the grid overlaying properly on the ground and going to toward the horizon rviz thinks the camera is pointed at the ground.

This example is running the gazebo_ros_demos rrbot_gazebo and rrbot_control launch files, and using standard Ubuntu 14.04 + Jade packages.

I cross posted https://github.com/ros-simulation/gaz... - or is it the fault of rviz/Camera and opencv, every node calling opencv camera projection functions should rotate first? Or every node on either side should have options to support either frame? (Or do options exist already and I've missed them?)

My short term solution is going to be to republish every frame out of gazebo with a rotated camera frame in the header (and the urdf/xacro can create the corrected frame, or it could be sent to tf from the same republishing node).

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
7

answered 2016-04-21 23:22:42 -0500

lucasw gravatar image

updated 2016-04-21 23:23:24 -0500

The xacro needs to create the optical frame like this, and the sensor uses it for frameName:

  <!-- generate an optical frame 
      http://www.ros.org/reps/rep-0103.html#suffix-frames
      so that ros and opencv can operate on the camera frame correctly 
      -->
  <joint name="camera_optical_joint" type="fixed">
    <!-- these values have to be these values otherwise the gazebo camera
        image won't be aligned properly with the frame it is supposedly
        originating from -->
    <origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
    <parent link="camera_link"/>
    <child link="camera_link_optical"/>
  </joint>

  <link name="camera_link_optical">
  </link>


  <gazebo reference="camera_link">
    <sensor type="camera" name="camera1">
      ...
      <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
        ...
        <frameName>camera_link_optical</frameName>
        ...

This shows the correctly generated optical frame- the Camera overlay RobotModel arm is seamless with the gazebo camera image:

image description

There is a PR for gazebo_ros_demos to get this fix in, since that is where the basic gazebo + ros tutorial points it really should be working correctly. https://github.com/ros-simulation/gaz...

It's possible the other gazebo ros sensors need to be handled similarly (but maybe the depth sensors had this solved within the plugin?).

edit flag offensive delete link more

Comments

Thanks a lot! This fix works very fine.

athul gravatar image athul  ( 2019-03-15 09:07:47 -0500 )edit

Can you do this purely with SDF model?

martinerk0 gravatar image martinerk0  ( 2021-04-14 16:03:19 -0500 )edit

This worked for me with the camera link having rpy="0 0 0", but I rotated the camera_link -${pi/2} in the roll axis ( rpy="-${pi/2} 0 0") and the image I get in rviz is rotated to the opposite side. Am I doing something wrong or is it supposed to be like this?

rezenders gravatar image rezenders  ( 2021-05-13 12:27:54 -0500 )edit
1

answered 2016-04-21 13:44:00 -0500

William gravatar image

I think ROS (rviz + rqt) are doing what they say they should:

From http://www.ros.org/reps/rep-0103.html... :

In the case of cameras, there is often a second frame defined with a "_optical" suffix. This uses a slightly different convention:

z forward
x right
y down

You might consider posting a link to this and/or the GitHub issue on http://answers.gazebosim.org/questions/ .

edit flag offensive delete link more

Comments

It looks like it is up to the user to supply the optical frame in <frameName>, and then they can generate the tf from the urdf or with their own tf transform send- and then it is up to the user to generate it correctly, I think instead the plugin should do it itself.

lucasw gravatar image lucasw  ( 2016-04-21 14:43:26 -0500 )edit
1

answered 2016-04-22 01:31:13 -0500

As @lucasw pointed out, it is up to the creator of the robot model to create the correct frames according to ROS conventions. Note this can be done within a xacro macro and this macro can then be instantiated easily in a model. For instance, the generic_camera macro can be used in models easily (example from here):

<xacro:generic_camera name="front_cam" parent="base_link" ros_topic="camera/image" cam_info_topic="camera/camera_info" update_rate="10" res_x="320" res_y="240" image_format="R8G8B8" hfov="90">
  <origin xyz="0.05 0.0 -0.06" rpy="0 0 0"/>
</xacro:generic_camera>
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2016-04-21 13:23:37 -0500

Seen: 7,064 times

Last updated: Apr 22 '16