From 266d8aa807572f4126981ef1f37902dffa87c2fe Mon Sep 17 00:00:00 2001 From: b1n-ch1kn Date: Tue, 17 Sep 2024 20:14:17 +1000 Subject: [PATCH] PR review changes --- .../steering_actuator/config/steering.yaml | 2 +- .../roscube_machine/launch/machine.launch.py | 8 +++---- .../config/slam_toolbox_params.yaml | 2 +- .../node_ebs_test_handler.py | 22 +++++++++++++++++-- 4 files changed, 26 insertions(+), 8 deletions(-) diff --git a/src/hardware/steering_actuator/config/steering.yaml b/src/hardware/steering_actuator/config/steering.yaml index c057611b3..71ca5a2d5 100644 --- a/src/hardware/steering_actuator/config/steering.yaml +++ b/src/hardware/steering_actuator/config/steering.yaml @@ -14,7 +14,7 @@ steering_actuator_node: centre_range: 2.0 centre_angle: -8.0 settling_iter: 50 - max_position: 2000 + max_position: 8500 Kp: 10.0 Ki: 0.0 Kd: 0.0 diff --git a/src/machines/roscube_machine/launch/machine.launch.py b/src/machines/roscube_machine/launch/machine.launch.py index 2329226e7..4eefe9447 100644 --- a/src/machines/roscube_machine/launch/machine.launch.py +++ b/src/machines/roscube_machine/launch/machine.launch.py @@ -76,10 +76,10 @@ def generate_launch_description(): ) ), ), - # Node( - # package="mission_controller", - # executable="mission_launcher_node", - # ), + Node( + package="mission_controller", + executable="mission_launcher_node", + ), IncludeLaunchDescription( launch_description_source=PythonLaunchDescriptionSource( launch_file_path=str(get_package_share_path("sensors") / "launch" / "vlp32.launch.py") diff --git a/src/navigation/nav_bringup/config/slam_toolbox_params.yaml b/src/navigation/nav_bringup/config/slam_toolbox_params.yaml index 3974683cd..a7be380c0 100644 --- a/src/navigation/nav_bringup/config/slam_toolbox_params.yaml +++ b/src/navigation/nav_bringup/config/slam_toolbox_params.yaml @@ -20,7 +20,7 @@ slam_toolbox_node: scan_queue_size: 1 # The number of scan messages to queue up before throwing away old ones. Should always be set to 1 in async mode use_map_saver: false # Instantiate the map saver service and self-subscribe to the map topic # map_start_pose: [0.0, 0.0, 0.0] # Pose to start pose-graph mapping/localization in, if available - debug_logging: true # Change logger to debug + debug_logging: false # Change logger to debug throttle_scans: 1 # Number of scans to throttle in synchronous mode transform_publish_period: 0.05 # The map to odom transform publish period. 0 will not publish transforms map_update_interval: 2.0 # Interval to update the 2D occupancy map for other applications / visualization diff --git a/src/operations/mission_controller/mission_controller/node_ebs_test_handler.py b/src/operations/mission_controller/mission_controller/node_ebs_test_handler.py index 3cb951f1c..1a8a30108 100644 --- a/src/operations/mission_controller/mission_controller/node_ebs_test_handler.py +++ b/src/operations/mission_controller/mission_controller/node_ebs_test_handler.py @@ -62,10 +62,28 @@ def __init__(self): ] self.get_logger().info(f"Running Command: {' '.join(command)}") cmd = Popen(command) - command = ["stdbuf", "-o", "L", "ros2", "param", "set", "steering_actuator_node", "max_position", "2000"] + command = [ + "stdbuf", + "-o", + "L", + "ros2", + "param", + "set", + "steering_actuator_node", + "max_position", + "2000", + ] self.get_logger().info(f"Running Command: {' '.join(command)}") cmd = Popen(command) - command = ["stdbuf", "-o", "L", "ros2", "launch", "mission_controller", "ebs_test.launch.py"] + command = [ + "stdbuf", + "-o", + "L", + "ros2", + "launch", + "mission_controller", + "ebs_test.launch.py", + ] self.get_logger().info(f"Running Command: {' '.join(command)}") self.process = Popen(command) self.get_logger().info("EBS mission started")