I am trying to do a camera pose calibration using multiple cameras. The camera_pose_calibration package in our setup with two Prosilica cameras is running pretty good (depending on the network (1Gbps), I sometimes receive the "Couldn't get measurement in interval" message). Unfortunately, when I try the same thing with the rectified images (RGB mono) of two kinects, the pose calibration is never capturing a calibration sample.
This is the current setup:
kinect2 on miniitx2 (Ubuntu 10.04 with ROS Diamondback)
kinect3 on miniitx3 (Ubuntu 10.04 with ROS Diamondback)
pma-09-042 (=PC from where I launch everything) (Ubuntu 10.04 with ROS Diamondback)
camera launch file:
<launch>
<!-- MACHINES -->
<machine name="miniitx2" address="192.168.10.72" user="common" default="never" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)">
<env name="ROS_IP" value="192.168.10.72" />
<env name="ROS_MASTER_URI" value="http://192.168.10.72:11311/" />
<env name="ROS_PACKAGE_PATH" value="/opt/ros/diamondback:$ROS_PACKAGE_PATH" />
</machine>
<machine name="miniitx3" address="192.168.10.73" user="common" default="never" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)">
<env name="ROS_IP" value="192.168.10.73" />
<env name="ROS_MASTER_URI" value="http://192.168.10.72:11311/" />
<env name="ROS_PACKAGE_PATH" value="/opt/ros/diamondback:$ROS_PACKAGE_PATH" />
</machine>
<!-- LAUNCH KINECT2 ON MINIITX2 -->
<node machine="miniitx2" ns="kinect2" pkg="nodelet" type="nodelet" name="manager" args="manager"/>
<!-- Driver nodelet -->
<node machine="miniitx2" ns="kinect2" pkg="nodelet" type="nodelet" name="openni_node2" args="load openni_camera/driver manager">
<param name="rgb_camera_info_url" value="file:///home/common/ros_seb/calibration_rgb.yaml" />
<param name="depth_camera_info_url" value="file:///home/common/ros_seb/calibration_depth.yaml" />
<param name="rgb_frame_id" type="str" value="kinect2" />
</node>
<node machine="miniitx2" ns="kinect2/rgb/" name="image_proc" pkg="image_proc" type="image_proc" output="screen" >
<remap from="image_raw" to="/kinect2/rgb/image_raw" />
<remap from="cam_info" to="/kinect2/rgb/camera_info" />
</node>
<!-- LAUNCH KINECT3 ON MINIITX3 -->
<node machine="miniitx3" ns="kinect3" pkg="nodelet" type="nodelet" name="manager" args="manager"/>
<!-- Driver nodelet -->
<node machine="miniitx3" ns="kinect3" pkg="nodelet" type="nodelet" name="openni_node3" args="load openni_camera/driver manager">
<param name="rgb_camera_info_url" value="file:///home/common/ros_seb/calibration_rgb.yaml" />
<param name="depth_camera_info_url" value="file:///home/common/ros_seb/calibration_depth.yaml" />
<param name="rgb_frame_id" type="str" value="kinect3" />
</node>
<node machine="miniitx3" ns="kinect3/rgb/" name="image_proc" pkg="image_proc" type="image_proc" output="screen" >
<remap from="image_raw" to="/kinect3/rgb/image_raw" />
<remap from="camera_info" to="/kinect3/rgb/camera_info" />
</node>
<!-- INCLUDES -->
<include file="$(find openni_camera)/launch/kinect_frames.launch" />
<include file="$(find camera_pose_calibration)/blocks/calibration_tf_publisher.launch" >
<arg name="cache_file" value="/tmp/camera_pose_calibration_cache.bag" />
</include>
</launch>
The calibrate_2_camera.launch file:
<launch>
<arg name="camera1_ns" default="kinect2/rgb" />
<arg name="camera2_ns" default="kinect3/rgb" />
<arg name="checker_rows" default="7"/>
<arg name="checker_cols" default="6"/>
<arg name="checker_size" default="0.108"/>
<arg name="headless" default="false" />
<!-- checkerboard detector for each camera -->
<include file="$(find camera_pose_calibration)/blocks/rgb_block.launch">
<arg name="ns" value="$(arg camera1_ns)" />
<arg name="checker_rows" value="$(arg checker_rows)" />
<arg name="checker_cols" value="$(arg checker_cols)" />
<arg name="checker_size" value="$(arg checker_size)" />
</include>
<include file="$(find camera_pose_calibration)/blocks/rgb_block.launch">
<arg name="ns" value="$(arg camera2_ns)" />
<arg name="checker_rows" value="$(arg checker_rows)" />
<arg name="checker_cols" value="$(arg checker_cols)" />
<arg name="checker_size" value="$(arg checker_size)" />
</include>
<!-- find time intervals where all camera's see a checkerboard -->
<node type="interval_intersection_action" pkg="interval_intersection" name="interval_intersection" output="screen" />
<node pkg="camera_pose_calibration" type="start_interval_intersection.py" name="start_interval_intersection"
args="$(arg camera1_ns) $(arg camera2_ns)" output="screen" />
<node pkg="camera_pose_calibration" type="filter_intervals.py" name="filter_intervals">
<param name="min_duration" value="1.0" />
<remap from="features" to="$(arg camera1_ns)/features" />
</node>
<!-- generate robot measurements -->
<node pkg="camera_pose_calibration" type="multicam_capture_exec.py" name="capture_exec"
args="$(arg camera1_ns) $(arg camera2_ns)" output="screen">
<param name="cam_info_topic" value="camera_info" />
<remap from="request_interval" to="interval_filtered" />
</node>
<!-- optimize camera poses -->
<node type="run_optimization_online.py" pkg="camera_pose_calibration" name="cal_optimizer" output="screen"/>
<!-- Visualization -->
<node type="capture_monitor.py" pkg="camera_pose_calibration" name="capture_monitor" output="screen"
args="$(arg camera1_ns) $(arg camera2_ns)" />
<node unless="$(arg headless)" type="image_view" pkg="image_view" name="aggregated_image_viewer" >
<remap from="image" to="aggregated_image" />
</node>
</launch>
Output:
There is one warning when launching the cameras:
[ WARN] [1314025889.212765938]: You've passed in true for auto_start for the C++ action server you should always pass in false to avoid race conditions.
Is that a problem?
This is the output of the calibrate_2_camera.launch file in my terminal:
sducatt@pma-09-042:~/ros_seb/launch_extrinsics$ roslaunch calibrate_2_camera_temp.launch
... logging to /home/sducatt/.ros/log/9de57c22-ccbb-11e0-b9e2-0001807c4485/roslaunch-pma-09-042.mech.kuleuven.be-22522.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://192.168.10.95:51803/
SUMMARY
========
PARAMETERS
* /rosversion
* /filter_intervals/min_duration
* /rosdistro
* /capture_exec/cam_info_topic
NODES
/kinect2/rgb/
image_throttle (topic_tools/throttle)
stereo_cb_detector (image_cb_detector/image_cb_detector_action_old)
start_cb_detector_action_old (camera_pose_calibration/start_cb_detector_action_old.py)
monocam_settler (monocam_settler/monocam_settler_action)
start_monocam_settler_action (camera_pose_calibration/start_monocam_settler_action.py)
/kinect3/rgb/
image_throttle (topic_tools/throttle)
stereo_cb_detector (image_cb_detector/image_cb_detector_action_old)
start_cb_detector_action_old (camera_pose_calibration/start_cb_detector_action_old.py)
monocam_settler (monocam_settler/monocam_settler_action)
start_monocam_settler_action (camera_pose_calibration/start_monocam_settler_action.py)
/
interval_intersection (interval_intersection/interval_intersection_action)
start_interval_intersection (camera_pose_calibration/start_interval_intersection.py)
filter_intervals (camera_pose_calibration/filter_intervals.py)
capture_exec (camera_pose_calibration_adjusted/multicam_capture_exec.py)
cal_optimizer (camera_pose_calibration/run_optimization_online.py)
capture_monitor (camera_pose_calibration/capture_monitor.py)
aggregated_image_viewer (image_view/image_view)
ROS_MASTER_URI=http://192.168.10.72:11311
core service [/rosout] found
process[kinect2/rgb/image_throttle-1]: started with pid [22531]
process[kinect2/rgb/stereo_cb_detector-2]: started with pid [22532]
process[kinect2/rgb/start_cb_detector_action_old-3]: started with pid [22533]
process[kinect2/rgb/monocam_settler-4]: started with pid [22534]
process[kinect2/rgb/start_monocam_settler_action-5]: started with pid [22535]
process[kinect3/rgb/image_throttle-6]: started with pid [22536]
process[kinect3/rgb/stereo_cb_detector-7]: started with pid [22537]
process[kinect3/rgb/start_cb_detector_action_old-8]: started with pid [22538]
process[kinect3/rgb/monocam_settler-9]: started with pid [22539]
process[kinect3/rgb/start_monocam_settler_action-10]: started with pid [22540]
process[interval_intersection-11]: started with pid [22552]
process[start_interval_intersection-12]: started with pid [22555]
process[filter_intervals-13]: started with pid [22565]
process[capture_exec-14]: started with pid [22570]
process[cal_optimizer-15]: started with pid [22577]
process[capture_monitor-16]: started with pid [22579]
process[aggregated_image_viewer-17]: started with pid [22580]
Configuring checkerboard size 7x6, checker size 0.108
Waiting for Server
Configuring checkerboard size 7x6, checker size 0.108
Waiting for Server
Waiting for Server
Found Server
Found Server
Creating aggregator for ['kinect2/rgb', 'kinect3/rgb']
[INFO] [WallTime: 1314019508.648921] Reset calibration state
Found Server
Both kinect cameras are visible in the aggregated view and the bars become green. There is no further action.
After a while (let's say 5-10 min, timeout?), I receive:
Got a request callback
Couldn't get measurement in interval
I have the impression there is no node sending the request callback. Despite a lot of trying and searching, I could not track down the problem.
Is it possible that the time intervals are not big enough? Where can I change those (my checkerboard or cameras are not moving)? Changing the parameter "min_duration" for the "filter_intervals" node isn't doing a lot.
Is there anyone with an idea or solution to solve this problem?
Thanks in advance,
Sébastien Ducatteeuw
EDIT:
Thanks for you reaction Wim!
By changing the "min_duration" parameter of the interval filters, I was able to fix the "Couldn't get measurement in interval" errors during the calibration of the Prosilica cameras.
The pose calibration with the Kinects was still not working after changing the "min_duration" parameter. The problem was caused by unsynchronized system clocks on the mini-itx boards. By doing a clock synchronization using ntpdate, the big time offset between image timestamps was eliminated (offset of +- 300s or 5min. = time I had to wait for my first "Got a request callback" message). In the case of the Procilica cameras, I never had that problem because I launched them all on the same pc.
Originally posted by Sébastien Ducatteeuw on ROS Answers with karma: 11 on 2011-08-22
Post score: 0