Depth thermal alignment
Hi Ros Community, I am trying to create a thermal depth point cloud with the intel real sense and the FLIR boson. I am using ros melodic on ubuntu 18.04. The packages I’m using are the realsense ros wrapper and the flir boson ros wrapper
I calibrated the thermal camera (attached is calibrationdata.tar.gz) and am noticing the rectification matrix is a diagonal matrix of ones.
ost.yaml contains:
image_width: 640
image_height: 512
camera_name: narrow_stereo
camera_matrix:
rows: 3
cols: 3
data: [ 559.69987, 0. , 209.74271,
0. , 552.85097, 304.20298,
0. , 0. , 1. ]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.229730, 0.060601, -0.017858, 0.060694, 0.000000]
rectification_matrix:
rows: 3
cols: 3
data: [ 1., 0., 0.,
0., 1., 0.,
0., 0., 1.]
projection_matrix:
rows: 3
cols: 4
data: [ 547.10474, 0. , 231.97042, 0. ,
0. , 539.98737, 300.37552, 0. ,
0. , 0. , 1. , 0. ]
My launch file ties these together like so:
<launch>
<arg name="namespace_thermal" default="flir_boson_usb"/>
<arg name="namespace_vis" default="realsense"/>
<!-- flir_boson_usb -->
<include file="$(find flir_boson_usb)/launch/flir_boson_rectified.launch">
<arg name="namespace" value="$(arg namespace_thermal)" />
<arg name="dev" value="/dev/video0" />
<arg name="frame_id" value = "thermal_cam_frame" />
<arg name="camera_info_url" value = "$(find thermal_depth)/BosonCalibration.yaml"/>
</include>
<!-- realsense -->
<include file="$(find realsense2_camera)/launch/rs_camera.launch" ns="$(arg namespace_vis)">
<arg name="filters" value="pointcloud" />
<arg name="tf_prefix" value="rs" />
</include>
<!-- tf2 -->
<node pkg="tf2_ros" type="static_transform_publisher" name="rs_2_thermal" args="-0.0219 -0.002 -0.029 0.0 0.0 0.0 rs_depth_optical_frame thermal_cam_frame" />
<!-- RVIZ -->
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find thermal_depth)/rviz/thermalDepth.rviz"/>
<!-- Depth_image_proc-->
<node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager" />
<node pkg="nodelet" type="nodelet" name="registerer"
args="load depth_image_proc/register nodelet_manager">
<!-- inputs-->
<remap from="rgb/camera_info" to="/flir_boson_usb/camera_info"/>
<remap from="depth/camera_info" to="/realsense/camera/depth/camera_info"/>
<remap from="depth/image_rect" to="/realsense/camera/depth/image_rect_raw"/>
<!-- outputs-->
<remap from="depth_registered/camera_info" to="registerer/camera_info"/>
<remap from="depth_registered/image_rect" to="registerer/image_rect"/>
</node>
<!--<node pkg="nodelet" type="nodelet" name="plainPoints"
args="load depth_image_proc/point_cloud_xyz nodelet_manager">
<remap from="camera_info" to="registerer/camera_info"/>
<remap from="image_rect" to="registerer/image_rect"/>
<remap from="points" to="uncolored_points"/>
</node> -->
<node pkg="nodelet" type="nodelet" name="thermalDepth"
args="load depth_image_proc/point_cloud_xyzrgb nodelet_manager">
<!-- inputs-->
<remap from="rgb/camera_info" to="/flir_boson_usb/camera_info"/>
<remap from="rgb/image_rect_color" to="/flir_boson_usb/image_rect"/>
<remap from="depth_registered/image_rect" to="registerer/image_rect"/>
<!-- outputs-->
<remap from="depth_registered/points" to="thermal_depth/points"/>
</node>
</launch>
The resulting thermal cloud is not properly aligned even though I’ve done the calibrations and measured out the static transform. What do you recommend I try next? Is there a way to edit the transforms in rqt_reconfigure? I need more karma before I can post photos so ...