-
Notifications
You must be signed in to change notification settings - Fork 47
/
Copy pathmy_motion_planning.launch
40 lines (32 loc) · 1.78 KB
/
my_motion_planning.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>
<!-- Vehicle Contorl -->
<include file="$(find runtime_manager)/launch_files/vehicle_socket.launch"/>
<!-- obstacle_avoid -->
<include file="$(find waypoint_planner)/launch/astar_avoid.launch"/>
<!-- velocity_set -->
<include file="$(find waypoint_planner)/launch/velocity_set.launch"/>
<!-- pure_pursuit -->
<!-- Copied $(find pure_pursuit)/launch/pure_pursuit.launch to use respawn attribute. -->
<arg name="is_linear_interpolation" default="True"/>
<arg name="publishes_for_steering_robot" default="False"/>
<arg name="add_virtual_end_waypoints" default="False"/>
<arg name="const_lookahead_distance" default="4.0"/>
<arg name="const_velocity" default="5.0"/>
<arg name="lookahead_ratio" default="2.0"/>
<arg name="minimum_lookahead_distance" default="6.0"/>
<!-- 0 = waypoints, 1 = provided constant velocity -->
<arg name="velocity_source" default="0"/>
<!-- rosrun waypoint_follower pure_pursuit -->
<node pkg="pure_pursuit" type="pure_pursuit" name="pure_pursuit" output="log" respawn="true" respawn_delay="10">
<param name="is_linear_interpolation" value="$(arg is_linear_interpolation)"/>
<param name="publishes_for_steering_robot" value="$(arg publishes_for_steering_robot)"/>
<param name="add_virtual_end_waypoints" value="$(arg add_virtual_end_waypoints)"/>
<param name="const_lookahead_distance" value="$(arg const_lookahead_distance)"/>
<param name="const_velocity" value="$(arg const_velocity)"/>
<param name="lookahead_ratio" value="$(arg lookahead_ratio)"/>
<param name="minimum_lookahead_distance" value="$(arg minimum_lookahead_distance)"/>
<param name="velocity_source" value="$(arg velocity_source)"/>
</node>
<!-- twist_filter -->
<include file="$(find twist_filter)/launch/twist_filter.launch"/>
</launch>