-
Notifications
You must be signed in to change notification settings - Fork 8
/
Copy pathodometry_transformer.launch
40 lines (34 loc) · 1.95 KB
/
odometry_transformer.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
<launch>
<!-- The original odometry source topic -->
<arg name="source_odometry" default="source_odometry"/>
<!-- The desired odometry target topic -->
<arg name="target_odometry" default="target_odometry"/>
<!-- The original odometry source frame id. -->
<arg name="source_frame" default="source"/>
<!-- The desired odometry target frame id. -->
<arg name="target_frame" default="target"/>
<!-- The static calibration from the target frame to the source frame in the target coordinate frame. -->
<!-- Rotation from target frame to source frame. Quaternion as [x,y,z,w] -->
<!-- See also https://www.andre-gaschler.com/rotationconverter/ -->
<arg name="q_TS" default="[0.0, 0.0, 0.0, 1.0]"/>
<!-- Translation from target frame to source frame. -->
<arg name="T_r_TS" default="[0.0, 0.0, 0.0]"/>
<!-- Instead of parametric calibration, the node can lookup the sensor calibration from TF. -->
<arg name="lookup_tf" default="false"/>
<!-- Queue size for odometry messages. -->
<arg name="queue_size" default="1"/>
<!-- Use tcpNoDelay() to subscribe to source odometry. Uses more CPU! -->
<!-- This is necessary to avoid message drops at high rate. It is not necessary when using nodelets or low rate odometry. -->
<arg name="tcp_no_delay" default="true" />
<node name="odometry_transformer" pkg="odometry_transformer" type="odometry_transformer_node" output="screen">
<remap from="source_odometry" to="$(arg source_odometry)"/>
<remap from="target_odometry" to="$(arg target_odometry)"/>
<param name="source_frame" value="$(arg source_frame)"/>
<param name="target_frame" value="$(arg target_frame)"/>
<rosparam param="q_TS" subst_value="True">$(arg q_TS)</rosparam>
<rosparam param="T_r_TS" subst_value="True">$(arg T_r_TS)</rosparam>
<param name="lookup_tf" value="$(arg lookup_tf)"/>
<param name="queue_size" value="$(arg queue_size)"/>
<param name="tcp_no_delay" value="$(arg tcp_no_delay)"/>
</node>
</launch>