Skip to content

Commit 0ce81ba

Browse files
committed
all cameras roughly calibrated
1 parent 951401c commit 0ce81ba

17 files changed

+1843
-32
lines changed

azure_kinect_ros_driver.patch

+13
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
diff --git a/launch/kinect_rgbd.launch b/launch/kinect_rgbd.launch
2+
index 4222a41..55113a4 100644
3+
--- a/launch/kinect_rgbd.launch
4+
+++ b/launch/kinect_rgbd.launch
5+
@@ -93,7 +93,7 @@
6+
<param name="point_cloud" value="$(arg point_cloud)" />
7+
<param name="rgb_point_cloud" value="$(arg rgb_point_cloud)" />
8+
<param name="point_cloud_in_depth_frame" value="$(arg point_cloud_in_depth_frame)" />
9+
- <param name="sensor_sn" value="$(arg sensor_sn)" />
10+
+ <param name="sensor_sn" type="string" value="$(arg sensor_sn)" />
11+
<param name="tf_prefix" value="$(arg tf_prefix)" />
12+
<param name="recording_file" value="$(arg recording_file)" />
13+
<param name="recording_loop_enabled" value="$(arg recording_loop_enabled)" />

config/table1.scene

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
(noname)+
1+
(noname)++
22
* cam0_beam
33
0.3564 0.254 0.4317
44
0 0 0 1
@@ -40,7 +40,7 @@ box
4040
0 0 0 0
4141
0
4242
* table
43-
0.4 -0.3175 -0.6
43+
0.4 -0.3175 -0.60635
4444
0 0 0 1
4545
1
4646
box

launch/aruco_single.launch

+8-8
Original file line numberDiff line numberDiff line change
@@ -1,22 +1,22 @@
11

22

33
<launch>
4-
54
<arg name="markerId" default="581"/>
6-
<arg name="markerSize" default="0.05"/> <!-- in m -->
7-
<arg name="cam_id" default="0"/>
8-
<arg name="marker_frame" default="aruco_marker_frame"/>
5+
<arg name="markerSize" default="0.045"/> <!-- in m -->
6+
<arg name="marker_frame" default="aruco"/>
97
<arg name="ref_frame" default=""/> <!-- leave empty and the pose will be published wrt param parent_name -->
8+
<arg name="camera_frame" default="k4a_0/rgb_camera_link"/>
9+
<arg name="camera_info_topic" default="/k4a_0/rgb/camera_info"/>
10+
<arg name="image_rect_color_topic" default="/k4a_0/rgb/image_rect_color"/>
1011

1112
<node pkg="aruco_ros" type="single" name="aruco_single">
12-
<remap from="/camera_info" to="/k4a_$(arg cam_id)/rgb/camera_info" />
13-
<remap from="/image" to="/k4a_$(arg cam_id)/rgb/image_rect_color" />
13+
<remap from="/camera_info" to="$(arg camera_info_topic)" />
14+
<remap from="/image" to="$(arg image_rect_color_topic)" />
1415
<param name="image_is_rectified" value="True"/>
1516
<param name="marker_size" value="$(arg markerSize)"/>
1617
<param name="marker_id" value="$(arg markerId)"/>
1718
<param name="reference_frame" value="$(arg ref_frame)"/> <!-- frame in which the marker pose will be refered -->
18-
<param name="camera_frame" value="$(arg cam_id)_rgb_camera_link"/>
19+
<param name="camera_frame" value="$(arg camera_frame)"/>
1920
<param name="marker_frame" value="$(arg marker_frame)_$(arg markerId)" />
2021
</node>
21-
2222
</launch>

launch/calibrate.launch

+74-9
Original file line numberDiff line numberDiff line change
@@ -1,19 +1,84 @@
11
<launch>
2-
<!-- (start your robot's MoveIt! stack, e.g. include its moveit_planning_execution.launch) -->
3-
<!-- (start your tracking system's ROS driver) -->
42

3+
<!-- CAMERA -->
4+
<arg name="camera_id" default="0"/>
5+
6+
<!-- Cameras:
7+
0: Left of the robot (closest to the computer)
8+
1: Across from the robot
9+
2: Right of the robot
10+
3: Directly next to the robot
11+
-->
12+
<!-- Derive the sensor serial name from the id indexing into this list. It's a bit of a hack.
13+
In a different robot configuration, you'd use something different. -->
14+
<arg name="sensor_sn" default="$(eval '000003493812,000180921812,000059793712,000263392612'.split(',')[arg('camera_id')])"/>
15+
16+
<!-- ROBOT -->
17+
<!-- Robot arguments. The defaults are for the franka, but you could change. -->
18+
<arg name="move_group" default="panda_arm"/>
19+
<arg name="robot_base_frame" default="panda_link0"/>
20+
<arg name="robot_effector_frame" default="panda_link8"/>
21+
22+
<!-- FIDUCIAL TAG DETECTION FRAME -->
23+
<arg name="aruco_marker_id" default="581"/>
24+
<arg name="aruco_marker_size" default="0.045"/>
25+
26+
<!-- CALIBRATION PROCEDURE -->
27+
<!-- The robot takes a bunch of measurements in different rotations. However,
28+
the final 4 measurements are a box in a plane, with 2x this value. Make this value as
29+
large as possible while still detecting the camera. -->
30+
<arg name="translation_delta_meters" default="0.2"/>
31+
32+
33+
<!-- Launch the camera driver -->
34+
<group ns="k4a_$(arg camera_id)">
35+
<include file="$(find azure_kinect_ros_driver)/launch/kinect_rgbd.launch">
36+
<arg name="sensor_sn" value="$(arg sensor_sn)"/>
37+
38+
<!-- Naming. -->
39+
<arg name="tf_prefix" value="k4a_$(arg camera_id)/"/>
40+
41+
<!-- Sensor properties -->
42+
<arg name="color_resolution" value="2160P"/>
43+
44+
<!-- ROS node properties. -->
45+
<arg name="required" value="true"/>
46+
<arg name="overwrite_robot_description" value="false"/>
47+
</include>
48+
</group>
49+
50+
<!-- Launch the tracker. -->
51+
<include file="$(find rpad_ros)/launch/aruco_single.launch">
52+
<arg name="markerId" value="$(arg aruco_marker_id)"/>
53+
<arg name="markerSize" value="$(arg aruco_marker_size)"/>
54+
<arg name="camera_frame" value="k4a_$(arg camera_id)/rgb_camera_link"/>
55+
<arg name="camera_info_topic" value="/k4a_$(arg camera_id)/rgb/camera_info"/>
56+
<arg name="image_rect_color_topic" value="/k4a_$(arg camera_id)/rgb/image_rect_color"/>
57+
</include>
58+
59+
<!-- Launch static publishers which describe the frame of the tag w.r.t. the robot. -->
60+
<include file="$(find rpad_ros)/launch/calibration_frame_publishers.launch" />
61+
62+
<!-- Launch the robot planning scene! -->
63+
<include file="$(find rpad_ros)/launch/table1_planning_scene.launch" />
64+
65+
<!-- Launch the calibration script, with RVIZ disabled (we have our own custom RVIZ configuration) -->
566
<include file="$(find easy_handeye)/launch/calibrate.launch">
667
<arg name="eye_on_hand" value="false"/>
7-
<arg name="namespace_prefix" value="my_eob_calib"/>
68+
<arg name="namespace_prefix" value="k4a_$(arg camera_id)"/>
869

970
<!-- fill in the following parameters according to your robot's published tf frames -->
10-
<arg name="move_group" value="panda_arm"/>
11-
<arg name="robot_base_frame" value="panda_link0"/>
12-
<arg name="robot_effector_frame" value="tagframe"/>
71+
<arg name="move_group" value="$(arg move_group)"/>
72+
<arg name="robot_base_frame" value="$(arg robot_base_frame)"/>
73+
<arg name="robot_effector_frame" value="$(arg robot_effector_frame)"/>
74+
<arg name="start_rviz" value="false"/>
1375

1476
<!-- fill in the following parameters according to your tracking system's published tf frames -->
15-
<arg name="tracking_base_frame" value="0_camera_base"/>
16-
<arg name="tracking_marker_frame" value="aruco_marker_frame_581"/>
17-
<arg name="translation_delta_meters" value="0.2"/>
77+
<arg name="tracking_base_frame" value="k4a_$(arg camera_id)/camera_base"/>
78+
<arg name="tracking_marker_frame" value="aruco_$(arg aruco_marker_id)"/>
79+
<arg name="translation_delta_meters" value="$(arg translation_delta_meters)"/>
1880
</include>
81+
82+
<!-- Launch rviz with saved stuff. -->
83+
<node type="rviz" name="rviz" pkg="rviz" args="-d $(find rpad_ros)/launch/calibrate.rviz" />
1984
</launch>

0 commit comments

Comments
 (0)