更新运动规划算法

This commit is contained in:
Robin Shaun 2020-07-10 17:56:53 +08:00
parent 780d012ef4
commit b589dcc035
7 changed files with 16 additions and 11 deletions

View File

@ -1,5 +1,5 @@
<launch>
<node pkg="tf" type="static_transform_publisher" name="odom_to_amp"
<node pkg="tf" type="static_transform_publisher" name="odom_to_map"
args="0.0 0.0 0 0.0 0.0 0.0 /odom /map 40" />
<!-- Arguments -->
<arg name="motion_planning" default="/home/robin/px4/xtdrone/motion_planning"/>
@ -7,7 +7,7 @@
<arg name="open_rviz" default="true"/>
<!-- Map server -->
<node pkg="map_server" name="map_server" type="map_server" args="$(arg motion_planning)/map//indoor3.yaml"/>
<node pkg="map_server" name="map_server" type="map_server" args="$(arg motion_planning)/map/indoor3.yaml"/>
<!-- move_base -->
<include file="$(arg motion_planning)/launch/move_base.launch">

View File

@ -7,6 +7,7 @@
<!-- move_base -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_global_planner" value="global_planner/GlobalPlanner" />
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
<rosparam file="$(arg motion_planning)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(arg motion_planning)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />
@ -14,6 +15,7 @@
<rosparam file="$(arg motion_planning)/param/global_costmap_params.yaml" command="load" />
<rosparam file="$(arg motion_planning)/param/move_base_params.yaml" command="load" />
<rosparam file="$(arg motion_planning)/param/dwa_local_planner_params.yaml" command="load" />
<rosparam file="$(arg motion_planning)/param/nav_core_params.yaml" command="load" />
<remap from="cmd_vel" to="$(arg cmd_vel_topic)"/>
<remap from="odom" to="$(arg odom_topic)"/>
<param name="DWAPlannerROS/min_vel_x" value="0.0" if="$(arg move_forward_only)" />

File diff suppressed because one or more lines are too long

View File

@ -1,6 +1,6 @@
image: /home/robin/px4/xtdrone/motion_planning/map/indoor3.pgm
resolution: 0.020000
origin: [-5.000000, -15.240000, 0.000000]
origin: [-5.300000, -5.3000, 0.000000]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.196

View File

@ -4,13 +4,13 @@ TrajectoryPlannerROS:
max_vel_x: 0.3
min_vel_x: 0.02
max_vel_theta: 0.1
min_vel_theta: -0.1
max_vel_theta: 2
min_vel_theta: -2
min_in_place_vel_theta: 1.0
acc_lim_x: 1.0
acc_lim_y: 0.0
acc_lim_theta: 0.3
acc_lim_y: 1
acc_lim_theta: 1
# Goal Tolerance Parameters
xy_goal_tolerance: 0.2

View File

@ -11,11 +11,11 @@ DWAPlannerROS:
max_trans_vel: 0.2
min_trans_vel: 0.01
max_rot_vel: 0.1
max_rot_vel: 0.5
min_rot_vel: 0.01
acc_lim_x: 1
acc_lim_y: 0.0
acc_lim_y: 1
acc_lim_theta: 1
# Goal Tolerance Parametes

View File

@ -0,0 +1,3 @@
BaseGlobalPlanner:
use_dijkstra : False