Skip to content
Snippets Groups Projects
Commit 25297e17 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Tuned the navigation parameters of the DWA local planner.

Changed the environment used for navigation.
parent b7c6bb85
No related branches found
No related tags found
1 merge request!8Kinetic migration
base_local_planner: "dwa_local_planner/DWAPlannerROS" base_local_planner: "dwa_local_planner/DWAPlannerROS"
DWAPlannerROS: DWAPlannerROS:
max_trans_vel: 0.24 max_trans_vel: 0.1
min_trans_vel: 0.01 min_trans_vel: 0.01
max_vel_x: 0.24 max_vel_x: 0.1
min_vel_x: -0.24 min_vel_x: -0.1
max_vel_y: 0.1 max_vel_y: 0.0
min_vel_y: -0.1 min_vel_y: 0.0
max_rot_vel: 0.1 max_rot_vel: 0.4
min_rot_vel: 0.01 min_rot_vel: 0.1
sim_time: 3 sim_time: 10
sim_granularity: 0.025 sim_granularity: 0.025
angular_sim_granularity: 0.1 angular_sim_granularity: 0.1
...@@ -26,14 +26,14 @@ DWAPlannerROS: ...@@ -26,14 +26,14 @@ DWAPlannerROS:
scaling_speed: 0.25 scaling_speed: 0.25
max_scaling_factor: 0.2 max_scaling_factor: 0.2
vx_samples: 10 vx_samples: 21
vy_samples: 10 vy_samples: 1
vth_samples: 20 vth_samples: 20
acc_lim_theta: 0.1 acc_lim_theta: 0.3
acc_lim_x: 0.1 acc_lim_x: 0.3
acc_lim_y: 0.1 acc_lim_y: 0.3
acc_limit_trans: 0.1 acc_limit_trans: 0.3
rot_stopped_vel: 0.01 rot_stopped_vel: 0.01
trans_stopped_vel: 0.01 trans_stopped_vel: 0.01
......
...@@ -5,8 +5,8 @@ ...@@ -5,8 +5,8 @@
name="qr_detector" name="qr_detector"
type="qr_detector" type="qr_detector"
output="screen"> output="screen">
<param name="qr_x" value="0.14"/> <param name="qr_x" value="0.2"/>
<param name="qr_y" value="0.14"/> <param name="qr_y" value="0.2"/>
<param name="camera_frame" value="/darwin/darwin_cam_link"/> <param name="camera_frame" value="/darwin/darwin_cam_link"/>
<remap from="~/camera/image_raw" to="/darwin/camera/image_raw"/> <remap from="~/camera/image_raw" to="/darwin/camera/image_raw"/>
<remap from="~/camera/camera_info" to="/darwin/camera/camera_info"/> <remap from="~/camera/camera_info" to="/darwin/camera/camera_info"/>
...@@ -16,7 +16,7 @@ ...@@ -16,7 +16,7 @@
name="qr_global_loc" name="qr_global_loc"
type="qr_global_loc" type="qr_global_loc"
output="screen"> output="screen">
<param name="qr_map_param" value="/charge_env/robot_description"/> <param name="qr_map_param" value="/obstacles_environment"/>
<param name="tf_prefix" value="/darwin"/> <param name="tf_prefix" value="/darwin"/>
<param name="publish_tf" value="True"/> <param name="publish_tf" value="True"/>
<param name="publish_rate" value="20"/> <param name="publish_rate" value="20"/>
......
...@@ -2,13 +2,13 @@ ...@@ -2,13 +2,13 @@
<launch> <launch>
<arg name="robot" default="darwin" /> <arg name="robot" default="darwin" />
<arg name="environment" default="charge_env" /> <arg name="environment" default="obstacles_env_empty" />
<include file="$(find darwin_description)/launch/darwin_sim.launch"> <include file="$(find darwin_description)/launch/darwin_sim.launch">
<arg name="robot" value="$(arg robot)" /> <arg name="robot" value="$(arg robot)" />
</include> </include>
<include file="$(find darwin_description)/launch/charge_env.launch"> <include file="$(find bioloid_description)/launch/obstacles_env.launch">
<arg name="environment" value="$(arg environment)" /> <arg name="environment" value="$(arg environment)" />
</include> </include>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment