Skip to content

Commit

Permalink
Tools: ros2: Reformat
Browse files Browse the repository at this point in the history
Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Sep 5, 2024
1 parent 4161231 commit 9231812
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
11 changes: 3 additions & 8 deletions Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
FALSE_STRING = "False"
BOOL_STRING_CHOICES = set([TRUE_STRING, FALSE_STRING])


class VirtualPortsLaunch:
"""Launch functions for creating virtual ports using `socat`."""

Expand Down Expand Up @@ -369,16 +370,10 @@ def generate_launch_arguments() -> List[DeclareLaunchArgument]:
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
),
]

Expand Down

0 comments on commit 9231812

Please sign in to comment.