-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathbringup_services.launch
More file actions
54 lines (45 loc) · 2.49 KB
/
bringup_services.launch
File metadata and controls
54 lines (45 loc) · 2.49 KB
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
52
53
54
<launch>
<arg name="multi_robot" default="false"/>
<arg name="wheel_diameter" default="0.165"/>
<arg name="wheel_separation" default="0.385"/>
<arg name="publish_frequency" default="10"/>
<arg name="publish_tranform" default="false"/>
<arg name="odom_link_frame" default="odom"/>
<arg name="base_link_frame" default="base_link"/>
<arg name="imu_link_frame" default="imu_link"/>
<!-- load robot description -->
<!-- <include file="$(find sr_description)/launch/srbot_empty_world.launch"/> -->
<!-- Load the URDF into the ROS Parameter Server -->
<param unless="$(arg multi_robot)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find sr_description)/urdf/srbot.urdf.xacro'" />
<node pkg="robot_state_publisher" type="robot_state_publisher"
name="robot_state_publisher" output="screen"/>
<!-- kinematic launch file -->
<!-- single_robot -->
<include unless="$(arg multi_robot)" file="$(find sr_kinematic)/launch/sr_kinematic.launch">
<arg name="wheel_diameter" value="$(arg wheel_diameter)"/>
<arg name="wheel_separation" value="$(arg wheel_separation)"/>
<arg name="publish_frequency" value="$(arg publish_frequency)"/>
<arg name="publish_tranform" value="$(arg publish_tranform)"/>
<arg name="odom_link_frame" default="odom"/>
<arg name="base_link_frame" default="base_link"/>
<arg name="imu_link_frame" default="imu_link"/>
</include>
<!-- multi_robot -->
<include if="$(arg multi_robot)" file="$(find sr_kinematic)/launch/sr_kinematic.launch">
<arg name="wheel_diameter" value="$(arg wheel_diameter)"/>
<arg name="wheel_separation" value="$(arg wheel_separation)"/>
<arg name="publish_frequency" value="$(arg publish_frequency)"/>
<arg name="publish_tranform" value="$(arg publish_tranform)"/>
<arg name="odom_link_frame" default="robot1_tf/odom"/>
<arg name="base_link_frame" default="robot1_tf/base_link"/>
<arg name="imu_link_frame" default="robot1_tf/imu_link"/>
</include>
<!-- setup sensor fusion by robot_localization node use EKF -->
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization" clear_params="true">
<rosparam command="load" file="$(find sr_bringup)/config/ekf.yaml"/>
<remap from="odometry/filtered" to="odom"/>
</node>
<include file="$(find sr_navigation)/launch/navigation.launch">
<arg name="multi_robot" value="$(arg multi_robot)"/>
</include>
</launch>