ros kinect calibration

RGB camera

Bring up the OpenNI driver: 

roslaunch openni_launch openni.launch

Now follow the standard monocular camera calibration instructions. Use the following command (substituting the correct dimensions of your checkerboard): 

rosrun camera_calibration cameracalibrator.py image:=/camera/rgb/image_raw camera:=/camera/rgb --size 5x4 --square 0.0245

Don't forget to Commit your successful calibration. 

IR (depth) camera

The Kinect detects depth by using an IR camera and IR speckle projector as a pseudo-stereo pair. We will calibrate the "depth" camera by detecting checkerboards in the IR image, just as we calibrated the RGB camera. 

The speckle pattern makes it impossible to detect the checkerboard corners accurately in the IR image. The simplest solution is to cover the projector (lone opening on the far left) with one or two Post-it notes, mostly diffusing the speckles. An ideal solution is to block the projector completely and provide a separate IR light source. Good illumination sources include sunlight, halogen lamps, or incandescent lamps. 

IR

IR covered

IR with speckle pattern

IR with projector covered by Post-it note

As before, follow the monocular camera calibration instructions: 

rosrun camera_calibration cameracalibrator.py image:=/camera/ir/image_raw camera:=/camera/ir --size 5x4 --square 0.0245

The Kinect camera driver cannot stream both IR and RGB images. It will decide which of the two to stream based on the amount of subscribers, so kill nodes that subscribe to RGB images before doing the IR calibration. 

Don't forget to Commit your successful calibration. 

Where are the intrinsics saved?

When you click Commit, cameracalibrator.py sends the new calibration to the camera driver as a service call. The driver immediately begins publishing the updated calibration on its camera_info topic. 

openni_camera uses camera_info_manager to manage calibration parameters. By default, it saves intrinsics to $HOME/.ros/camera_info/NAME.yaml and identifies them by the device serial number: 

$ ls ~/.ros/camera_info/
depth_B00362708888047B.yaml  rgb_B00362708888047B.yaml

Whenever you bring up the OpenNI driver, it will look for a previously saved calibration. If you want to share the intrinsics among multiple users, move them somewhere public (e.g. /public/path/) and use a launch file which configures the camera info URLs: 

<launch>

 <!-- Include official launch file and specify camera_info urls -->
 <include file="$(find openni_launch)/launch/openni.launch">
   <!-- provide arguments to that launch file -->
 <arg name="rgb_camera_info_url"  value="file:///public/path/rgb_B00362708888047B.yaml" />  <arg name="depth_camera_info_url"  value="file:///public/path/depth_B00362708888047B.yaml" />  </include>  </launch>
 

Wiki: openni_launch/Tutorials/IntrinsicCalibration (last edited 2015-02-06 01:36:34 by AlexanderReimann)

http://wiki.ros.org/openni_launch/Tutorials/IntrinsicCalibration

猜你喜欢

转载自www.cnblogs.com/2008nmj/p/10283999.html
今日推荐