This repository has been archived by the owner on Nov 9, 2021. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 29
/
lawn_tractor_sim.launch
63 lines (52 loc) · 3.17 KB
/
lawn_tractor_sim.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
52
53
54
55
56
57
58
59
60
61
62
63
<!-- file: robot_in_stage.launch -->
<launch>
<!-- ************** Global Parameters *************** -->
<param name="/use_sim_time" value="true"/>
<!-- ************** Stage Simulator *************** -->
<node pkg="stage_ros" type="stageros" name="stageros"
args="-g runs headless $(find lawn_tractor_sim)/stage/farm.world">
<remap from="base_scan" to="scan"/>
</node>
<!-- ************** Robot Description *************** -->
<!-- robot_description is used by nodes that publish to joint_states. -->
<param name="robot_description"
command="$(find xacro)/xacro --inorder $(find lawn_tractor_sim)/urdf/lawn_tractor.urdf.xacro"/>
<!-- Read joint positions from joint_states, then publish the vehicle's
state to tf. -->
<node name="vehicle_state_publisher" pkg="robot_state_publisher"
type="robot_state_publisher">
<param name="publish_frequency" value="30.0"/>
</node>
<!-- ****** Move Base Flex ***** -->
<node pkg="mbf_costmap_nav" type="mbf_costmap_nav" respawn="false" name="move_base_flex" output="screen">
<param name="tf_timeout" value="1.5"/>
<param name="planner_max_retries" value="3"/>
<rosparam file="$(find lawn_tractor_navigation)/config/planners.yaml" command="load" />
<rosparam file="$(find lawn_tractor_navigation)/config/controllers.yaml" command="load" />
<rosparam file="$(find lawn_tractor_navigation)/config/recovery_behaviors.yaml" command="load" />
<rosparam file="$(find lawn_tractor_navigation)/config/costmap_common_params.yaml" command="load" ns="global_costmap"/>
<rosparam file="$(find lawn_tractor_navigation)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find lawn_tractor_navigation)/config/global_costmap_params.yaml" command="load" />
<rosparam file="$(find lawn_tractor_navigation)/config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find lawn_tractor_navigation)/config/teb_local_planner_params_carlike.yaml"
command="load" />
</node>
<!--The below is the old SMACH based code, leaving commented code here temporarily-->
<!-- <node pkg="lawn_tractor_navigation" name="mbf_state_machine" type="mbf_state_machine.py" respawn="false" output="screen"/> -->
<node pkg="lawn_tractor_navigation" name="mbf_behavior_tree" type="movebaseflex_bt_node" respawn="false" output="screen" />
<!-- ****** Maps ***** -->
<node name="map_server" pkg="map_server" type="map_server"
args="$(find lawn_tractor_sim)/maps/farm.yaml" output="screen">
<param name="frame_id" value="map"/>
</node>
<!-- ****** Fake localization for map and gps ***** -->
<node pkg="tf" type="static_transform_publisher" name="map_to_odom" args="0.0 0.0 0.0 0 0 0.0 /map /odom 100"/>
<node pkg="tf" type="static_transform_publisher" name="map_to_utm" args="0.0 0.0 0.0 0 0 0.0 /map /utm 100"/>
<node pkg="lawn_tractor_sim" type="odom_to_lla.py" name="odom_to_lla" output="screen"/>
<!-- ****** RVIZ ***** -->
<node name="tractor_viz" pkg="rviz" type="rviz" output="screen"
args="-d $(find lawn_tractor_sim)/rviz/tractor_viz.rviz">
</node>
<!-- ****** Markers ***** -->
<node name="obstacles" pkg="lawn_tractor_sim" type="shapes" output="screen" />
</launch>