mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2025-05-16 09:48:05 +00:00
Compare commits
5 Commits
a57d981e71
...
53d07ef946
Author | SHA1 | Date | |
---|---|---|---|
|
53d07ef946 | ||
|
2e9e571cdf | ||
|
f401327c69 | ||
|
55b58950f4 | ||
|
804bdb23e8 |
41
config/dwa_base_local_planner_params.yaml
Normal file
41
config/dwa_base_local_planner_params.yaml
Normal file
@ -0,0 +1,41 @@
|
||||
controller_frequency: 5.0
|
||||
recovery_behavior_enabled: false
|
||||
clearing_rotation_allowed: false
|
||||
|
||||
DWAPlannerROS:
|
||||
max_vel_trans: 1.0
|
||||
min_vel_trans: 0.2
|
||||
max_vel_x: 1.0
|
||||
min_vel_x: 0.2
|
||||
max_vel_y: 0.0 # zero for a differential drive robot
|
||||
min_vel_y: 0.0
|
||||
min_in_place_vel_theta: 0.5
|
||||
escape_vel: -0.1
|
||||
acc_lim_x: 0.5
|
||||
acc_lim_y: 0.0 # zero for a differential drive robot
|
||||
acc_lim_theta: 1.0
|
||||
|
||||
holonomic_robot: false
|
||||
yaw_goal_tolerance: 0.1 # about 6 degrees
|
||||
xy_goal_tolerance: 0.15 # 10 cm
|
||||
latch_xy_goal_tolerance: false
|
||||
pdist_scale: 0.8
|
||||
gdist_scale: 0.6
|
||||
meter_scoring: true
|
||||
|
||||
heading_lookahead: 0.325
|
||||
heading_scoring: false
|
||||
heading_scoring_timestep: 0.8
|
||||
occdist_scale: 0.1
|
||||
oscillation_reset_dist: 0.05
|
||||
publish_cost_grid_pc: false
|
||||
prune_plan: true
|
||||
|
||||
sim_time: 2.5
|
||||
sim_granularity: 0.025
|
||||
angular_sim_granularity: 0.025
|
||||
vx_samples: 8
|
||||
vy_samples: 0 # zero for a differential drive robot
|
||||
vtheta_samples: 20
|
||||
dwa: true
|
||||
simple_attractor: false
|
@ -9,11 +9,12 @@
|
||||
|
||||
<!--move base-->
|
||||
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
|
||||
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
|
||||
<rosparam file="$(find segwayrmp)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
|
||||
<rosparam file="$(find segwayrmp)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />
|
||||
<rosparam file="$(find segwayrmp)/param/local_costmap_params.yaml" command="load" />
|
||||
<rosparam file="$(find segwayrmp)/param/global_costmap_params.yaml" command="load" />
|
||||
<rosparam file="$(find segwayrmp)/param/base_local_planner_params.yaml" command="load" />
|
||||
<rosparam file="$(find cps_rmp220_support)/config/dwa_base_local_planner_params.yaml" command="load" />
|
||||
<!-- scan topic -->
|
||||
<remap from="scan" to="scan_filtered"/>
|
||||
<!-- remap cmd_vel -->
|
||||
@ -27,4 +28,4 @@
|
||||
static_transform_publisher x y z yaw pitch roll frame_id child_frame_id period_in_ms -->
|
||||
<!-- <node pkg="tf" type="static_transform_publisher" name="base_footprint_to_base_link" args="0 0 0.5 0 0 0 base_link base_footprint 50" /> -->
|
||||
|
||||
</launch>
|
||||
</launch>
|
||||
|
Loading…
Reference in New Issue
Block a user