Only released in EOL distros:  

robot_calibration: camera_offsetter

Package Summary

Provides a tool to make small changes to the location of a monocular camera or stereocamera attached to the robot. This package is still an unstable and experimental package. The interface is a work in progress that will be changing.

robot_calibration: camera_offsetter

Package Summary

Provides a tool to make small changes to the location of a monocular camera or stereocamera attached to the robot. This package is still an unstable and experimental package. The interface is a work in progress that will be changing.

robot_calibration: camera_offsetter

Package Summary

Provides a tool to make small changes to the location of a monocular camera or stereocamera attached to the robot. This package is still an unstable and experimental package. The interface is a work in progress that will be changing.

Stability

This is still an experimental application that has not been reviewed yet. Its interface quite possibly will be changing.

Overview

The package creates a virtual camera, allows the user to move it and republishes raw sensor (stereo) data in the virtual camera. You can use it to fix calibration problems locally by eliminating obvious disparities between the 3D laser or robot data and stereo/image data.

offsetter_high_level.png

The package contains 3 main nodes:

  • mono_offsetter - Creates a virtual monocular camera and republishes camera_info and various image topics

  • stereo_offsetter - Creates a virtual stereo camera and republishes camera_info and image_raw topics

  • keyboard_interface - Sends simple twist and baseline offsets using the keyboard.

Limitations

The calibration is done manually and is only as good as you hand tune it. Also keep in mind that a perfect calibration in one part of the workspace will not necessarily result in a perfect calibration in another part of the workspace.

It is possible that the calibration problem is caused by something else, so keep your eyes open.

Creating a Virtual Camera (Node API)

mono_offsetter

Offset a monocular camera, such as the PR2's Hi-Res Prosilica cam or its forearm cameras

Subscribed Topics

virtual_pose (geometry_msgs/Pose)
  • Set the offset to be the incoming pose
virtual_twist (geometry_msgs/Twist)
  • Change the offset by the specified twist
[camera]/camera_info (sensor_msgs/CameraInfo)
  • Used to offset camera info. Always enabled
[camera]/image_raw,image_rect,image_rect_color (sensor_msgs/Image)
  • Used to offset images. Respectively enabled by the ~use_raw, ~use_rect, and ~use_rect_color parameters.

Published Topics

[camera]_offset/camera_info (sensor_msgs/CameraInfo)
  • Used to offset camera info. Always enabled
[camera]_offset/image_raw,image_rect,image_rect_color (sensor_msgs/Image)
  • Used to publish offset images. Respectively enabled by the ~use_raw, ~use_rect, and ~use_rect_color parameters.

Parameters

~config_file (string, default: False)
  • Filename to for reading/writing the most recent offset
~use_raw (bool, default: False)
  • If True, then offsetter republishes image_raw
~use_rect (bool, default: False)
  • If True, then offsetter republishes image_rect
~use_rect_color (bool, default: False)
  • If True, then offsetter republishes image_rect_color

Example

Suppose that you want to offset a camera in the /prosilica namespace. You could use the following launch file:

<launch>
  <node type="mono_offsetter" pkg="camera_offsetter" name="prosilica_offsetter">
    <remap from="camera" to="/prosilica" />
    <param name="config_file" type="string" value="[HOME_DIR]/prosilica.offset" />
    <param name="use_rect_color" type="bool" value="True" />
  </node>
</launch>

This launches a camera_offsetter that subscribes to /prosilica/image_rect_color and /prosilica/camera_info. It copies the data from these messages, appends _offset to the frame_ids, and republishes on prosilica_offset/image_rect_color and /prosilica/camera_info.

stereo_offsetter

Offset a stereo camera

Subscribed Topics

virtual_pose (geometry_msgs/Pose)
  • Set the offset to be the incoming pose
virtual_twist (geometry_msgs/Twist)
  • Change the offset by the specified twist
baseline_factor (std_msgs/Float64)
  • Change the stereocamera baseline by the specified factor
[stereo]/left/camera_info, [stereo]/right/camera_info (sensor_msgs/CameraInfo)
  • Used to offset left & right camera info
[stereo]/left/image_raw, [stereo]/right/image_raw (sensor_msgs/Image)
  • Used to offset left & right raw images

Published Topics

[stereo]_offset/left/camera_info, [stereo]_offset/right/camera_info (sensor_msgs/CameraInfo)
  • Used to offset left & right camera info
[stereo]_offset/left/image_raw, [stereo]_offset/right/image_raw (sensor_msgs/Image)
  • Used to publish offset left & right images

Parameters

~config_file (string, default: False)
  • Filename to for reading/writing the most recent offset

Suppose that you want to offset a stereocamera in the /narrow_stereo namespace. You could use the following launch file:

<launch>
  <node type="stereo_offsetter" pkg="camera_offsetter" name="stereo_offsetter">
    <remap from="stereo" to="/narrow_stereo" />
    <param name="config_file" type="string" value="[HOME_DIR]/narrow.offset" />
  </node>

  <group ns="narrow_stereo_offset">
    <node type="stereo_image_proc" name="proc" pkg="stereo_image_proc"/>
  </group>
</launch>

This will create a virtual stereocamera in the /narrow_stereo_offset namespace. This file also launches the stereo_image_proc node on the offset camera.

Use the keyboard to move a virtual camera (Node API)

keyboard_interface

Sends incremental pose offsets as twists. Can also send baseline updates for virtual stereocameras

Published Topics

virtual_pose (geometry_msgs/Pose)
  • Set the offset to be the incoming pose
virtual_twist (geometry_msgs/Twist)
  • Change the offset by the specified twist
baseline_factor (std_msgs/Float64)
  • Change the stereocamera baseline by the specified factor

Command Line Usage

  • In translation mode, keys x/X, y/Y, z/Z move the virtual camera in fixed increments (e.g. x=-0.001, X=+0.001).
  • In rotation mode, keys x/X, y/Y, z/Z rotate the virtual camera around respective axis
  • In baseline mode, keys b/B increase or decrease the stereocamera baseline

Example

To start the keyboard interface, all you need to do is start the node in the same namespace as the offsetter. If the offsetter is in the global namespace, then a simple rosrun is sufficient:

rosrun camera_offsetter keyboard_interface

Wiki: camera_offsetter (last edited 2010-10-15 21:36:04 by VijayPradeep)