Skip to content

Commit b196d6c

Browse files
committed
Add default params file
Signed-off-by: Maria Teresa Ortega <teresa.ortega0903@gmail.com>
1 parent fc546bb commit b196d6c

3 files changed

Lines changed: 111 additions & 6 deletions

File tree

examples/beluga_launch.py

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,12 @@ def generate_launch_description():
1616
Returns:
1717
LaunchDescription: The complete ROS 2 launch description object.
1818
"""
19+
config_file_arg = DeclareLaunchArgument(
20+
"beluga_config_path",
21+
default_value="/example/defaul_params.ros.yaml", # Opcional por defecto
22+
description="Absolute YAML file path",
23+
)
24+
1925
map_path_arg = DeclareLaunchArgument("map_path", description="Absolute map path")
2026

2127
laser_model_arg = DeclareLaunchArgument(
@@ -28,9 +34,6 @@ def generate_launch_description():
2834
max_particles_arg = DeclareLaunchArgument(
2935
"max_particles", default_value="2000", description="Max number of particles"
3036
)
31-
laser_topic_arg = DeclareLaunchArgument(
32-
"laser_topic", default_value="/scan", description="Topic for laser sensor"
33-
)
3437

3538
beluga_node = Node(
3639
package="beluga_amcl",
@@ -41,7 +44,6 @@ def generate_launch_description():
4144
{
4245
"laser_model_type": LaunchConfiguration("laser_model_type"),
4346
"max_particles": LaunchConfiguration("max_particles"),
44-
"laser_topic": LaunchConfiguration("scan_topic"),
4547
}
4648
],
4749
)
@@ -64,12 +66,12 @@ def generate_launch_description():
6466

6567
return LaunchDescription(
6668
[
69+
config_file_arg,
6770
map_path_arg,
6871
laser_model_arg,
6972
max_particles_arg,
7073
beluga_node,
7174
map_server_node,
7275
lifecycle_manager_node,
73-
laser_topic_arg,
7476
]
7577
)

examples/default.ros2.yaml

Lines changed: 103 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,103 @@
1+
amcl:
2+
ros__parameters:
3+
# Odometry motion model type.
4+
robot_model_type: nav2_amcl::DifferentialMotionModel
5+
# Expected process noise in odometry’s rotation estimate from rotation.
6+
alpha1: 0.1
7+
# Expected process noise in odometry’s rotation estimate from translation.
8+
alpha2: 0.05
9+
# Expected process noise in odometry’s translation estimate from translation.
10+
alpha3: 0.1
11+
# Expected process noise in odometry’s translation estimate from rotation.
12+
alpha4: 0.05
13+
# Expected process noise in odometry's strafe estimate from translation.
14+
alpha5: 0.1
15+
# The name of the coordinate frame published by the localization system.
16+
global_frame_id: map
17+
# The name of the coordinate frame published by the odometry system.
18+
odom_frame_id: odom
19+
# The name of the coordinate frame of the robot base.
20+
base_frame_id: base_footprint
21+
# The name of the topic where the map is published by the map server.
22+
map_topic: map
23+
# The name of the topic where scans are being published.
24+
scan_topic: scan
25+
# The name of the topic where an initial pose can be published.
26+
# The particle filter will be reset using the provided pose with covariance.
27+
initial_pose_topic: initialpose
28+
# Maximum number of particles that will be used.
29+
max_particles: 2000
30+
# Minimum number of particles that will be used.
31+
min_particles: 500
32+
# Error allowed by KLD criteria.
33+
pf_err: 0.05
34+
# KLD criteria parameter.
35+
# Upper standard normal quantile for the probability that the error in the
36+
# estimated distribution is less than pf_err.
37+
pf_z: 3.0
38+
# Fast exponential filter constant, used to filter the average particles weights.
39+
# Random particles are added if the fast filter result is larger than the slow filter result
40+
# allowing the particle filter to recover from a bad approximation.
41+
recovery_alpha_fast: 0.1
42+
# Slow exponential filter constant, used to filter the average particles weights.
43+
# Random particles are added if the fast filter result is larger than the slow filter result
44+
# allowing the particle filter to recover from a bad approximation.
45+
recovery_alpha_slow: 0.001
46+
# Resample will happen after the amount of updates specified here happen.
47+
resample_interval: 1
48+
# Minimum angle difference from last resample for resampling to happen again.
49+
update_min_a: 0.2
50+
# Maximum angle difference from last resample for resampling to happen again.
51+
update_min_d: 0.25
52+
# Laser sensor model type.
53+
laser_model_type: likelihood_field
54+
# Maximum distance of an obstacle (if the distance is higher, this one will be used in the likelihood map).
55+
laser_likelihood_max_dist: 2.0
56+
# Maximum range of the laser.
57+
laser_max_range: 100.0
58+
# Maximum number of beams to use in the likelihood field sensor model.
59+
max_beams: 100
60+
# Weight used to combine the probability of hitting an obstacle.
61+
z_hit: 0.5
62+
# Weight used to combine the probability of random noise in perception.
63+
z_rand: 0.5
64+
# Whether to model unknown space or assume it free.
65+
model_unknown_space: true
66+
# Weight used to combine the probability of getting short readings.
67+
z_short: 0.05
68+
# Weight used to combine the probability of getting max range readings.
69+
z_max: 0.05
70+
# Standard deviation of a gaussian centered arounds obstacles.
71+
sigma_hit: 0.2
72+
# Whether to broadcast map to odom transform or not.
73+
tf_broadcast: true
74+
# Transform tolerance allowed.
75+
transform_tolerance: 1.0
76+
# Execution policy used to apply the motion update and importance weight steps.
77+
# Valid options: "seq", "par".
78+
execution_policy: seq
79+
# Whether to set initial pose based on parameters.
80+
# When enabled, particles will be initialized with the specified pose coordinates and covariance.
81+
set_initial_pose: true
82+
# If false, AMCL will use the last known pose to initialize when a new map is received.
83+
always_reset_initial_pose: false
84+
# Set this to true when you want to load only the first published map from map_server and ignore subsequent ones.
85+
first_map_only: false
86+
# Initial pose x coordinate.
87+
initial_pose.x: 0.0
88+
# Initial pose y coordinate.
89+
initial_pose.y: 0.0
90+
# Initial pose yaw coordinate.
91+
initial_pose.yaw: 0.0
92+
# Initial pose xx covariance.
93+
initial_pose.covariance_x: 0.25
94+
# Initial pose yy covariance.
95+
initial_pose.covariance_y: 0.25
96+
# Initial pose yawyaw covariance.
97+
initial_pose.covariance_yaw: 0.0685
98+
# Initial pose xy covariance.
99+
initial_pose.covariance_xy: 0.0
100+
# Initial pose xyaw covariance.
101+
initial_pose.covariance_xyaw: 0.0
102+
# Initial pose yyaw covariance.
103+
initial_pose.covariance_yyaw: 0.0

src/lambkin/lambkin.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414
qos_file_path = "/ws/beluga/beluga_example/bags/qos_override.yaml"
1515

1616

17-
LASER_MODELS = ["likelihood", "beam"]
17+
LASER_MODELS = ["likelihood_field", "beam"]
1818
NUM_PARTICLES = [1, 10, 100, 1000, 10000]
1919
CLOCK_RATE_OPTION = ["--clock-rate", str(clock_rate)]
2020
QOS_OPTION = ["--qos-profile-overrides-path", qos_file_path]

0 commit comments

Comments
 (0)