From 25297e1742d5bbf4ed869588735e7d224c76e3ab Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Sergi=20Hern=C3=A0ndez=20Juan?= <shernand@iri.upc.edu> Date: Sun, 16 Jul 2017 21:23:52 +0200 Subject: [PATCH] Tuned the navigation parameters of the DWA local planner. Changed the environment used for navigation. --- .../config/dwa_local_planner_params.yaml | 30 +++++++++---------- .../launch/darwin_global_loc_sim.launch | 6 ++-- darwin_nav/launch/darwin_nav_sim.launch | 4 +-- 3 files changed, 20 insertions(+), 20 deletions(-) diff --git a/darwin_nav/config/dwa_local_planner_params.yaml b/darwin_nav/config/dwa_local_planner_params.yaml index 974a25a..d33edd4 100644 --- a/darwin_nav/config/dwa_local_planner_params.yaml +++ b/darwin_nav/config/dwa_local_planner_params.yaml @@ -1,16 +1,16 @@ base_local_planner: "dwa_local_planner/DWAPlannerROS" DWAPlannerROS: - max_trans_vel: 0.24 + max_trans_vel: 0.1 min_trans_vel: 0.01 - max_vel_x: 0.24 - min_vel_x: -0.24 - max_vel_y: 0.1 - min_vel_y: -0.1 - max_rot_vel: 0.1 - min_rot_vel: 0.01 - - sim_time: 3 + max_vel_x: 0.1 + min_vel_x: -0.1 + max_vel_y: 0.0 + min_vel_y: 0.0 + max_rot_vel: 0.4 + min_rot_vel: 0.1 + + sim_time: 10 sim_granularity: 0.025 angular_sim_granularity: 0.1 @@ -26,14 +26,14 @@ DWAPlannerROS: scaling_speed: 0.25 max_scaling_factor: 0.2 - vx_samples: 10 - vy_samples: 10 + vx_samples: 21 + vy_samples: 1 vth_samples: 20 - acc_lim_theta: 0.1 - acc_lim_x: 0.1 - acc_lim_y: 0.1 - acc_limit_trans: 0.1 + acc_lim_theta: 0.3 + acc_lim_x: 0.3 + acc_lim_y: 0.3 + acc_limit_trans: 0.3 rot_stopped_vel: 0.01 trans_stopped_vel: 0.01 diff --git a/darwin_nav/launch/darwin_global_loc_sim.launch b/darwin_nav/launch/darwin_global_loc_sim.launch index c8581e1..849aaf9 100644 --- a/darwin_nav/launch/darwin_global_loc_sim.launch +++ b/darwin_nav/launch/darwin_global_loc_sim.launch @@ -5,8 +5,8 @@ name="qr_detector" type="qr_detector" output="screen"> - <param name="qr_x" value="0.14"/> - <param name="qr_y" value="0.14"/> + <param name="qr_x" value="0.2"/> + <param name="qr_y" value="0.2"/> <param name="camera_frame" value="/darwin/darwin_cam_link"/> <remap from="~/camera/image_raw" to="/darwin/camera/image_raw"/> <remap from="~/camera/camera_info" to="/darwin/camera/camera_info"/> @@ -16,7 +16,7 @@ name="qr_global_loc" type="qr_global_loc" 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="publish_tf" value="True"/> <param name="publish_rate" value="20"/> diff --git a/darwin_nav/launch/darwin_nav_sim.launch b/darwin_nav/launch/darwin_nav_sim.launch index 3cf80c4..0d1e93e 100644 --- a/darwin_nav/launch/darwin_nav_sim.launch +++ b/darwin_nav/launch/darwin_nav_sim.launch @@ -2,13 +2,13 @@ <launch> <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"> <arg name="robot" value="$(arg robot)" /> </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)" /> </include> -- GitLab