forked from jhu-lcsr/handeye_calib_camodocal
-
Notifications
You must be signed in to change notification settings - Fork 0
/
handeye_file.launch
51 lines (42 loc) · 3.14 KB
/
handeye_file.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
<launch>
<!-- TF names-->
<!-- AR Tag TF frame, the ros topic for the tf frame seen by the camera sensor,
this need not be an actual AR tag, for example, it could be an optical tracker
marker, or a position on the gripper you detect directly -->
<arg name="ARTagTF" default="/ar_marker_0" />
<!-- Camera Transform, the ros topic for the tf frame of your camera sensor -->
<arg name="cameraTF" default="/camera_link" />
<!-- End Effector Transform, the ros topic for the tf frame
at the tip of your robot's gripper or other tool -->
<arg name="EETF" default="/ee_link" />
<!-- Robot Base Transform, the ros topic for the base tf frame of your robot -->
<arg name="baseTF" default="/base_link" />
<!-- The data folder where solver data should be saved and loaded from.
Defaults to the handeye_calib_camodocal/launch folder of this repository. -->
<arg name="data_folder" default="$(find handeye_calib_camodocal)/example" />
<!-- When you record transforms from a live running robot to a file,
and when you load that file from disk this is the filename that will be loaded.
After it is saved be sure to back this file up if you don't want it to be
overwritten by accident!
-->
<arg name="filename" default="TransformPairsInput.yml" />
<!-- The actual transform result you are solving for is saved with this filename -->
<arg name="calibrated_filename" default="CalibratedTransform.yml" />
<!-- tag the solver summary along the transform in the calibrated filename -->
<arg name="add_solver_summary" default="false" doc='Save a summary of the solver results in addition to the transforms in the calibrated output file. The summary includes the "ArmTipToMarkerTagTransform", "initial_cost", "final_cost, "change_cost", "termination_type", "num_successful_iteration", "num_unsuccessful_iteration", "num_iteration"'/>
<node pkg="handeye_calib_camodocal" type="handeye_calib_camodocal" name="handeye_calib_camodocal" output="screen">
<!-- handeye_calib_camodocal arg pass -->
<param name="ARTagTF" type="str" value="$(arg ARTagTF)" />
<param name="cameraTF" type="str" value="$(arg cameraTF)" />
<param name="EETF" type="str" value="$(arg EETF)" />
<param name="baseTF" type="str" value="$(arg baseTF)" />
<param name="load_transforms_from_file" type="bool" value="true"/>
<!-- tag the solver summary along the transformm in the calibrated filename -->
<param name="add_solver_summary" type="bool" value="$(arg add_solver_summary)"/>
<!-- When you record transforms from a live running robot to a file, this is where the file is saved -->
<param name="transform_pairs_record_filename" type="str" value="$(arg data_folder)/$(arg filename)" />
<!-- When you load transforms you saved to a file earlier, this is where the file is saved -->
<param name="transform_pairs_load_filename" type="str" value="$(arg data_folder)/$(arg filename)" />
<param name="output_calibrated_transform_filename" type="str" value="$(arg data_folder)/$(arg calibrated_filename)" />
</node>
</launch>