From c16fee3f47312b16f999b63933515a0b79d47560 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Thu, 5 Sep 2024 17:46:27 -0600 Subject: [PATCH] Tools: ros2: Reformat Signed-off-by: Ryan Friedman --- .../ardupilot_dds_tests/plane_waypoint_follower.py | 2 +- .../ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py | 11 +++-------- 2 files changed, 4 insertions(+), 9 deletions(-) diff --git a/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/plane_waypoint_follower.py b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/plane_waypoint_follower.py index 27de6f272f..5f00a3fb93 100755 --- a/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/plane_waypoint_follower.py +++ b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/plane_waypoint_follower.py @@ -144,7 +144,7 @@ def achieved_goal(goal_global_pos, cur_geopose): p2 = (cur_pos.latitude, cur_pos.longitude, cur_pos.altitude) flat_distance = distance.distance(p1[:2], p2[:2]).m - euclidian_distance = math.sqrt(flat_distance**2 + (p2[2] - p1[2]) ** 2) + euclidian_distance = math.sqrt(flat_distance ** 2 + (p2[2] - p1[2]) ** 2) print(f"Goal is {euclidian_distance} meters away") return euclidian_distance < 150 diff --git a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py index a85ddefc4e..15ef9bc9e3 100644 --- a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py +++ b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py @@ -35,6 +35,7 @@ TRUE_STRING = "True" FALSE_STRING = "False" BOOL_STRING_CHOICES = set([TRUE_STRING, FALSE_STRING]) + class VirtualPortsLaunch: """Launch functions for creating virtual ports using `socat`.""" @@ -369,16 +370,10 @@ class MAVProxyLaunch: description="SITL output port.", ), DeclareLaunchArgument( - "map", - default_value="False", - description="Enable MAVProxy Map.", - choices=BOOL_STRING_CHOICES + "map", default_value="False", description="Enable MAVProxy Map.", choices=BOOL_STRING_CHOICES ), DeclareLaunchArgument( - "console", - default_value="False", - description="Enable MAVProxy Console.", - choices=BOOL_STRING_CHOICES + "console", default_value="False", description="Enable MAVProxy Console.", choices=BOOL_STRING_CHOICES ), ]