Skip to content

Commit fd2879b

Browse files
committed
Capitalize and address some review comments
Signed-off-by: Maria Teresa Ortega <teresa.ortega0903@gmail.com>
1 parent c6cceaf commit fd2879b

File tree

2 files changed

+13
-12
lines changed

2 files changed

+13
-12
lines changed
Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,8 @@ def generate_launch_description():
1717
LaunchDescription: The complete ROS 2 launch description object.
1818
"""
1919
config_file_arg = DeclareLaunchArgument(
20-
"beluga_config_path",
21-
default_value="/example/defaul_params.ros.yaml", # Opcional por defecto
20+
"params_file",
21+
default_value="/example/defaul_params.ros.yaml",
2222
description="Absolute YAML file path",
2323
)
2424

@@ -41,10 +41,11 @@ def generate_launch_description():
4141
name="beluga_amcl",
4242
output="screen",
4343
parameters=[
44+
LaunchConfiguration("params_file"),
4445
{
4546
"laser_model_type": LaunchConfiguration("laser_model_type"),
4647
"max_particles": LaunchConfiguration("max_particles"),
47-
}
48+
},
4849
],
4950
)
5051

src/lambkin/lambkin.py

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -5,19 +5,19 @@
55
import time
66
from pathlib import Path
77

8-
reference_bag_path = (
8+
REFERENCE_BAG_PATH = (
99
"/ws/rosbags/magazzino_ros2_localization_only/bagfiles/hallway_localization/"
1010
)
11-
reference_map_path = "/ws/rosbags/maps/map.yaml"
12-
num_iterations = 1
13-
clock_rate = 10
14-
qos_file_path = "/ws/beluga/beluga_example/bags/qos_override.yaml"
11+
REFERENCE_MAP_PATH = "/ws/rosbags/maps/map.yaml"
12+
NUM_ITERATIONS = 1
13+
CLOCK_RATE = 10
14+
QOS_FILE_PATH = "/ws/beluga/beluga_example/bags/qos_override.yaml"
1515

1616

1717
LASER_MODELS = ["likelihood_field", "beam"]
1818
NUM_PARTICLES = [1, 10, 100, 1000, 10000]
19-
CLOCK_RATE_OPTION = ["--clock-rate", str(clock_rate)]
20-
QOS_OPTION = ["--qos-profile-overrides-path", qos_file_path]
19+
CLOCK_RATE_OPTION = ["--clock-rate", str(CLOCK_RATE)]
20+
QOS_OPTION = ["--qos-profile-overrides-path", QOS_FILE_PATH]
2121
CLOCK_OPTION = "--clock"
2222
RECORD_TOPICS_INTERESTED = ["/pose", "/tf", "/tf_static"]
2323
RESULTS_PATH = "/ws/lambkin/benchmarking_results"
@@ -296,9 +296,9 @@ def run_iteration(
296296
def main():
297297
"""Main loop that orchestrates the benchmarking process."""
298298
for variation in make_variations():
299-
for it in range(num_iterations):
299+
for it in range(NUM_ITERATIONS):
300300
run_iteration(
301-
variation, it, reference_map_path, reference_bag_path, DRY_MODE
301+
variation, it, REFERENCE_MAP_PATH, REFERENCE_BAG_PATH, DRY_MODE
302302
)
303303

304304

0 commit comments

Comments
 (0)