mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2025-04-28 17:59:00 +00:00
Compare commits
23 Commits
53d07ef946
...
019a359a5c
Author | SHA1 | Date | |
---|---|---|---|
|
019a359a5c | ||
|
838c88e1c7 | ||
|
922abd4df1 | ||
|
6a884433a4 | ||
|
26622cb900 | ||
|
9a6257e927 | ||
|
8a298d13a2 | ||
|
9480836dc3 | ||
|
49b9fe7c8c | ||
|
6b31575f3f | ||
|
86f55418e6 | ||
|
393d4b5183 | ||
|
d9c2207e0b | ||
|
7b51435adc | ||
|
9e6053754b | ||
|
5dc18212ea | ||
|
212bd9b946 | ||
|
34f4a2c80a | ||
|
455d73e0fa | ||
|
4e9ffb9406 | ||
|
bd1037133b | ||
|
fccec769ad | ||
|
f217658f66 |
9
config/costmap_common_params.yaml
Normal file
9
config/costmap_common_params.yaml
Normal file
@ -0,0 +1,9 @@
|
||||
obstacle_range: 2.5
|
||||
raytrace_range: 3.0
|
||||
#robot_radius: 0.25
|
||||
footprint: "[ [0.18, 0.200], [0.18, -0.200], [-0.54, -0.165], [-0.54, 0.165] ]"
|
||||
inflation_radius: 0.15
|
||||
max_obstacle_height: 0.6
|
||||
min_obstacle_height: 0.0
|
||||
observation_sources: scan
|
||||
scan: {data_type: LaserScan, topic: /scan_filtered, marking: true, clearing: true, expected_update_rate: 0}
|
@ -1,15 +1,15 @@
|
||||
controller_frequency: 5.0
|
||||
recovery_behavior_enabled: false
|
||||
clearing_rotation_allowed: false
|
||||
controller_frequency: 3.0 #20.0 #5.0
|
||||
recovery_behavior_enabled: true #false
|
||||
clearing_rotation_allowed: true #false
|
||||
|
||||
DWAPlannerROS:
|
||||
max_vel_trans: 1.0
|
||||
min_vel_trans: 0.2
|
||||
min_vel_trans: 0.1 #0.2
|
||||
max_vel_x: 1.0
|
||||
min_vel_x: 0.2
|
||||
min_vel_x: 0.1 #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
|
||||
min_in_place_vel_theta: 0.1 #0.5
|
||||
escape_vel: -0.1
|
||||
acc_lim_x: 0.5
|
||||
acc_lim_y: 0.0 # zero for a differential drive robot
|
||||
@ -21,21 +21,31 @@ DWAPlannerROS:
|
||||
latch_xy_goal_tolerance: false
|
||||
pdist_scale: 0.8
|
||||
gdist_scale: 0.6
|
||||
meter_scoring: true
|
||||
#meter_scoring: true
|
||||
|
||||
heading_lookahead: 0.325
|
||||
heading_scoring: false
|
||||
heading_lookahead: 1.5 #0.325
|
||||
heading_scoring: true #false
|
||||
heading_scoring_timestep: 0.8
|
||||
occdist_scale: 0.1
|
||||
#occdist_scale: 0.1
|
||||
oscillation_reset_dist: 0.05
|
||||
publish_cost_grid_pc: false
|
||||
prune_plan: true
|
||||
|
||||
sim_time: 2.5
|
||||
# Forward Simulation Parameters
|
||||
sim_time: 5.0 #1.0 #5.0 #2.5
|
||||
sim_granularity: 0.025
|
||||
angular_sim_granularity: 0.025
|
||||
vx_samples: 8
|
||||
vy_samples: 0 # zero for a differential drive robot
|
||||
vx_samples: 20 #8
|
||||
vy_samples: 1 #0 # zero for a differential drive robot
|
||||
vtheta_samples: 20
|
||||
dwa: true
|
||||
simple_attractor: false
|
||||
|
||||
# # Trajectory Scoring Parameters
|
||||
path_distance_bias: 64.0 # 32.0 - weighting for how much it should stick to the global path plan
|
||||
goal_distance_bias: 24.0 # 24.0 - wighting for how much it should attempt to reach its goal
|
||||
occdist_scale: 50.0 #2.0 #0.5 # 0.01 - weighting for how much the controller should avoid obstacles
|
||||
forward_point_distance: 0.325 # 0.325 - how far along to place an additional scoring point
|
||||
stop_time_buffer: 0.2 # 0.2 - amount of time a robot must stop in before colliding for a valid traj.
|
||||
scaling_speed: 0.25 # 0.25 - absolute velocity at which to start scaling the robot's footprint
|
||||
max_scaling_factor: 0.2 # 0.2 - how much to scale the robot's footprint when at speed.
|
||||
|
10
config/global_costmap_params.yaml
Normal file
10
config/global_costmap_params.yaml
Normal file
@ -0,0 +1,10 @@
|
||||
global_costmap:
|
||||
global_frame: map
|
||||
robot_base_frame: base_link
|
||||
update_frequency: 1.0 # 1.0
|
||||
publish_frequency: 1.0 #0
|
||||
static_map: true
|
||||
rolling_window: false
|
||||
resolution: 0.01
|
||||
transform_tolerance: 0.5
|
||||
map_type: costmap
|
12
config/local_costmap_params.yaml
Normal file
12
config/local_costmap_params.yaml
Normal file
@ -0,0 +1,12 @@
|
||||
local_costmap:
|
||||
global_frame: map #odom
|
||||
robot_base_frame: base_link
|
||||
update_frequency: 5.0 #1.0
|
||||
publish_frequency: 1.0
|
||||
static_map: false
|
||||
rolling_window: true
|
||||
width: 6.0
|
||||
height: 6.0
|
||||
resolution: 0.01
|
||||
transform_tolerance: 0.5
|
||||
map_type: costmap
|
@ -10,24 +10,33 @@
|
||||
<arg name="initial_pose_a" default="0.0"/>
|
||||
|
||||
<!-- ********** AMCL algorithm *********** -->
|
||||
<node pkg="amcl" type="amcl" name="amcl">
|
||||
<!-- <node pkg="amcl" type="amcl" name="amcl"> -->
|
||||
<node pkg="amcl" type="amcl" name="amcl" output="screen">
|
||||
<param name="min_particles" value="500"/>
|
||||
<param name="max_particles" value="3000"/>
|
||||
<!-- <param name="max_particles" value="3000"/> -->
|
||||
<param name="max_particles" value="5000"/>
|
||||
<param name="kld_err" value="0.02"/>
|
||||
<param name="update_min_d" value="0.20"/>
|
||||
<param name="update_min_a" value="0.20"/>
|
||||
<!-- <param name="update_min_a" value="0.20"/> -->
|
||||
<param name="update_min_a" value="0.50"/>
|
||||
<param name="resample_interval" value="1"/>
|
||||
<param name="transform_tolerance" value="0.5"/>
|
||||
<param name="recovery_alpha_slow" value="0.00"/>
|
||||
<param name="recovery_alpha_fast" value="0.00"/>
|
||||
<!-- <param name="transform_tolerance" value="0.5"/> -->
|
||||
<param name="transform_tolerance" value="0.1"/>
|
||||
<!-- <param name="recovery_alpha_slow" value="0.00"/> -->
|
||||
<param name="recovery_alpha_slow" value="0.001"/>
|
||||
<!-- <param name="recovery_alpha_fast" value="0.00"/> -->
|
||||
<param name="recovery_alpha_fast" value="0.01"/>
|
||||
<param name="initial_pose_x" value="$(arg initial_pose_x)"/>
|
||||
<param name="initial_pose_y" value="$(arg initial_pose_y)"/>
|
||||
<param name="initial_pose_a" value="$(arg initial_pose_a)"/>
|
||||
<param name="gui_publish_rate" value="50.0"/>
|
||||
<!-- <param name="gui_publish_rate" value="50.0"/> -->
|
||||
<param name="gui_publish_rate" value="20.0"/>
|
||||
|
||||
<remap from="scan" to="$(arg scan_topic)"/>
|
||||
<param name="laser_max_range" value="16.0"/>
|
||||
<param name="laser_max_beams" value="180"/>
|
||||
<!-- <param name="laser_max_range" value="16.0"/> -->
|
||||
<param name="laser_max_range" value="12.0"/>
|
||||
<!-- <param name="laser_max_beams" value="180"/> -->
|
||||
<param name="laser_max_beams" value="60"/>
|
||||
<param name="laser_z_hit" value="0.5"/>
|
||||
<param name="laser_z_short" value="0.05"/>
|
||||
<param name="laser_z_max" value="0.05"/>
|
||||
@ -37,16 +46,22 @@
|
||||
<param name="laser_likelihood_max_dist" value="2.0"/>
|
||||
<param name="laser_model_type" value="likelihood_field"/>
|
||||
|
||||
<!-- odom paramters: may raise alphas to compensate for bad odometry-->
|
||||
<param name="odom_model_type" value="diff"/>
|
||||
<param name="odom_alpha1" value="0.1"/>
|
||||
<param name="odom_alpha2" value="0.1"/>
|
||||
<param name="odom_alpha3" value="0.1"/>
|
||||
<param name="odom_alpha4" value="0.1"/>
|
||||
<!-- <param name="odom_alpha1" value="0.1"/> -->
|
||||
<param name="odom_alpha1" value="1.0"/>
|
||||
<!-- <param name="odom_alpha2" value="0.1"/> -->
|
||||
<param name="odom_alpha2" value="1.0"/>
|
||||
<!-- <param name="odom_alpha3" value="0.1"/> -->
|
||||
<param name="odom_alpha3" value="3.0"/>
|
||||
<!-- <param name="odom_alpha4" value="0.1"/> -->
|
||||
<param name="odom_alpha4" value="1.0"/>
|
||||
<param name="odom_frame_id" value="odom"/>
|
||||
<param name="base_frame_id" value="base_link"/>
|
||||
<!--
|
||||
<param name="global_frame_id" value="map"/>
|
||||
<param name="tf_broadcast" value="true" /> -->
|
||||
<param name="tf_broadcast" value="true" />
|
||||
|
||||
<!-- scan topic -->
|
||||
<!-- <remap from="scan" to="scan_filtered"/> -->
|
||||
|
@ -5,15 +5,15 @@
|
||||
|
||||
<!-- Run the map server -->
|
||||
<!-- <node name="map_server" pkg="map_server" type="map_server" args="$(find segwayrmp)/maps/mymap.pgm my_map_resolution"/> -->
|
||||
<node name="map_server" pkg="map_server" type="map_server" args="$(find cps_rmp220_support)/maps/map.yaml"/>
|
||||
<node name="map_server" pkg="map_server" type="map_server" args="/maps/map.yaml"/>
|
||||
|
||||
<!--move base-->
|
||||
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
|
||||
<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/costmap_common_params.yaml" command="load" ns="global_costmap" />
|
||||
<rosparam file="$(find cps_rmp220_support)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
|
||||
<rosparam file="$(find cps_rmp220_support)/config/local_costmap_params.yaml" command="load" />
|
||||
<rosparam file="$(find cps_rmp220_support)/config/global_costmap_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 -->
|
||||
@ -72,4 +72,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>
|
||||
|
@ -10,17 +10,18 @@
|
||||
<!--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 cps_rmp220_support)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
|
||||
<rosparam file="$(find cps_rmp220_support)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
|
||||
<rosparam file="$(find cps_rmp220_support)/config/local_costmap_params.yaml" command="load" />
|
||||
<rosparam file="$(find cps_rmp220_support)/config/global_costmap_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 -->
|
||||
<remap from="cmd_vel" to="nav_vel"/>
|
||||
<!-- remap odom -->
|
||||
<remap from="odom" to="/robot_pose_ekf/odom_combined"/>
|
||||
<!-- <remap from="odom" to="/robot_pose_ekf/odom_combined"/> -->
|
||||
<remap from="odom" to="/odom_new"/>
|
||||
</node>
|
||||
|
||||
<!-- TF -->
|
||||
|
@ -104,12 +104,19 @@ class EncoderOdometry:
|
||||
|
||||
# Include Covariance Matrix
|
||||
# Include covariance
|
||||
odom.pose.covariance = [0.01, 0, 0, 0, 0, 0,
|
||||
0, 0.01, 0, 0, 0, 0,
|
||||
0, 0, 0.01, 0, 0, 0,
|
||||
0, 0, 0, 0.01, 0, 0,
|
||||
0, 0, 0, 0, 0.01, 0,
|
||||
0, 0, 0, 0, 0, 0.01]
|
||||
# odom.pose.covariance = [0.01, 0, 0, 0, 0, 0,
|
||||
# 0, 0.01, 0, 0, 0, 0,
|
||||
# 0, 0, 0.01, 0, 0, 0,
|
||||
# 0, 0, 0, 0.01, 0, 0,
|
||||
# 0, 0, 0, 0, 0.01, 0,
|
||||
# 0, 0, 0, 0, 0, 0.01]
|
||||
|
||||
odom.pose.covariance = [0.1, 0, 0, 0, 0, 0, # Higher uncertainty in x
|
||||
0, 0.1, 0, 0, 0, 0, # Higher uncertainty in y
|
||||
0, 0, 0.2, 0, 0, 0, # Higher uncertainty in z (less typical for most robots)
|
||||
0, 0, 0, 0.5, 0, 0, # Higher uncertainty in roll
|
||||
0, 0, 0, 0, 0.5, 0, # Higher uncertainty in pitch
|
||||
0, 0, 0, 0, 0, 0.5] # Higher uncertainty in yaw
|
||||
|
||||
# Publish odometry to /odom_new
|
||||
rospy.logdebug("Publishing Odometry message.")
|
||||
|
Loading…
Reference in New Issue
Block a user