diff --git a/.github/ISSUE_TEMPLATE/navigator.yaml b/.github/ISSUE_TEMPLATE/navigator.yaml
index 8e528b706..a3617fae6 100644
--- a/.github/ISSUE_TEMPLATE/navigator.yaml
+++ b/.github/ISSUE_TEMPLATE/navigator.yaml
@@ -7,26 +7,6 @@ body:
attributes:
value: |
Hey, thanks for taking the time to add this software issue!
- - type: input
- id: assignee
- attributes:
- label: Assignee
- description: >
- Does this issue need to be completed by a specific person on the team?
- If so, mention them below.
- placeholder: ex. @torvalds is already working on this task!
- validations:
- required: false
- - type: input
- id: deadline
- attributes:
- label: Deadline
- description: >
- Does this task need a deadline? _If this task is related to a competition,
- it should have a deadline._
- placeholder: ex. 2023-12-25
- validations:
- required: false
- type: textarea
id: description
attributes:
diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml
index a99604c0e..de7c09a7a 100644
--- a/.github/workflows/ci.yaml
+++ b/.github/workflows/ci.yaml
@@ -31,6 +31,7 @@ jobs:
- name: Configure catkin workspace folder structure
run: |
mkdir -p $GITHUB_WORKSPACE/catkin_ws/src
+ sudo apt reinstall python3-pip
- name: Check out code from GitHub
uses: actions/checkout@v3.0.2
with:
diff --git a/.github/workflows/gh_pages.yaml b/.github/workflows/gh_pages.yaml
index b54342c28..39b70c62a 100644
--- a/.github/workflows/gh_pages.yaml
+++ b/.github/workflows/gh_pages.yaml
@@ -20,7 +20,7 @@ jobs:
# Wait for the CI to finish so we can download the docs artifact
- name: Wait for CI
- uses: lewagon/wait-on-check-action@v1.0.0
+ uses: lewagon/wait-on-check-action@v1.3.3
if: github.event.action != 'closed'
with:
ref: ${{ github.event.pull_request.head.ref }}
diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml
index 5db81ae41..79a11871a 100644
--- a/.pre-commit-config.yaml
+++ b/.pre-commit-config.yaml
@@ -11,15 +11,15 @@ ci:
repos:
- repo: https://github.com/adrienverge/yamllint.git
- rev: v1.32.0
+ rev: v1.33.0
hooks:
- id: yamllint
- repo: https://github.com/psf/black
- rev: 23.7.0
+ rev: 24.1.1
hooks:
- id: black
- repo: https://github.com/pre-commit/mirrors-clang-format
- rev: v16.0.6
+ rev: v17.0.6
hooks:
- id: clang-format
- repo: https://github.com/PyCQA/autoflake
@@ -28,24 +28,24 @@ repos:
- id: autoflake
args: [--remove-all-unused-imports, --ignore-init-module-imports]
- repo: https://github.com/shellcheck-py/shellcheck-py
- rev: v0.9.0.5
+ rev: v0.9.0.6
hooks:
- id: shellcheck
exclude: ^docker|deprecated|NaviGator/simulation/VRX
args: [--severity=warning, --exclude=SC1090]
- repo: https://github.com/scop/pre-commit-shfmt
- rev: v3.7.0-1
+ rev: v3.7.0-4
hooks:
- id: shfmt
exclude: ^docker|deprecated|NaviGator/simulation/VRX
- repo: https://github.com/astral-sh/ruff-pre-commit
# Ruff version.
- rev: 'v0.0.287'
+ rev: 'v0.2.0'
hooks:
- id: ruff
args: [--fix, --exit-non-zero-on-fix]
- repo: https://github.com/codespell-project/codespell
- rev: v2.2.5
+ rev: v2.2.6
hooks:
- id: codespell
args:
@@ -73,11 +73,12 @@ repos:
- id: prettier-package-xml
- id: sort-package-xml
- repo: https://github.com/pre-commit/pre-commit-hooks
- rev: v4.4.0
+ rev: v4.5.0
hooks:
- id: check-added-large-files
- id: check-case-conflict
- id: check-merge-conflict
+ exclude_types: [markdown, rst]
- id: check-executables-have-shebangs
- id: check-symlinks
- id: check-json
diff --git a/NaviGator/gnc/navigator_path_planner/nodes/path_planner.py b/NaviGator/gnc/navigator_path_planner/nodes/path_planner.py
index ba33ca850..1f6ff6793 100755
--- a/NaviGator/gnc/navigator_path_planner/nodes/path_planner.py
+++ b/NaviGator/gnc/navigator_path_planner/nodes/path_planner.py
@@ -1070,7 +1070,7 @@ def reevaluate_plan(self) -> None:
def action_check(self, _: rospy.timer.TimerEvent) -> None:
"""
Manages action preempting. Serves as the callback to a Timer operating
- opereating every self.revisit_period seconds.
+ operating every self.revisit_period seconds.
"""
if self.preempted or not self.move_server.is_active():
return
diff --git a/NaviGator/hardware_drivers/navigator_kill_board/navigator_kill_board/constants.py b/NaviGator/hardware_drivers/navigator_kill_board/navigator_kill_board/constants.py
index 83663e034..d5eaef7e4 100644
--- a/NaviGator/hardware_drivers/navigator_kill_board/navigator_kill_board/constants.py
+++ b/NaviGator/hardware_drivers/navigator_kill_board/navigator_kill_board/constants.py
@@ -17,6 +17,7 @@
The computer can also command a kill (for example, if ROS notices a criticaly low battery)
by sending the COMPUTER.KILL.REQUEST and undone with COMPUTER.CLEAR.REQUEST
"""
+
constants = {
"TIMEOUT_SECONDS": 8.0, # How often board must be pinged to not set HEARTBERAT_REMOTE True
# Note: not official documented, this is just a guess
diff --git a/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/battery_voltage.py b/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/battery_voltage.py
index 6c25b9169..c10b13c91 100644
--- a/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/battery_voltage.py
+++ b/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/battery_voltage.py
@@ -27,9 +27,9 @@ def _check_voltage(self, msg):
if not self._raised or self._severity != severity:
self.broadcaster.raise_alarm(
severity=severity,
- problem_description="battery critcaly low"
- if severity == 2
- else "battery low",
+ problem_description=(
+ "battery critcaly low" if severity == 2 else "battery low"
+ ),
parameters={"voltage": voltage},
)
diff --git a/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/odom_kill.py b/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/odom_kill.py
index 2bc5e6c43..d0fa63afd 100755
--- a/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/odom_kill.py
+++ b/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/odom_kill.py
@@ -51,9 +51,7 @@ def check_continuity(self, odom):
self._raised = True # Avoid raising multiple times
rospy.logwarn("ODOM DISCONTINUITY DETECTED")
self.ab.raise_alarm(
- problem_description="ODOM DISCONTINUITY DETECTED. JUMPED {} METERS".format(
- jump,
- ),
+ problem_description=f"ODOM DISCONTINUITY DETECTED. JUMPED {jump} METERS",
severity=5,
)
self.last_position = position
diff --git a/NaviGator/mission_control/navigator_launch/launch/vrx/vrx_master.launch b/NaviGator/mission_control/navigator_launch/launch/vrx/vrx_master.launch
index 944df5bfa..377f824de 100644
--- a/NaviGator/mission_control/navigator_launch/launch/vrx/vrx_master.launch
+++ b/NaviGator/mission_control/navigator_launch/launch/vrx/vrx_master.launch
@@ -7,6 +7,7 @@
+
@@ -30,5 +31,4 @@
-
diff --git a/NaviGator/mission_control/navigator_launch/launch/vrx/vrx_tf.launch b/NaviGator/mission_control/navigator_launch/launch/vrx/vrx_tf.launch
index f46bcca90..a9bdd66e8 100644
--- a/NaviGator/mission_control/navigator_launch/launch/vrx/vrx_tf.launch
+++ b/NaviGator/mission_control/navigator_launch/launch/vrx/vrx_tf.launch
@@ -1,5 +1,8 @@
+
+ true
+
@@ -11,9 +14,10 @@
-
-
-
-
+
+
+
+
+
diff --git a/NaviGator/mission_control/navigator_missions/launch/mission_params.yaml b/NaviGator/mission_control/navigator_missions/launch/mission_params.yaml
index 7b44edc7e..c4ee5940c 100644
--- a/NaviGator/mission_control/navigator_missions/launch/mission_params.yaml
+++ b/NaviGator/mission_control/navigator_missions/launch/mission_params.yaml
@@ -157,14 +157,14 @@ dock_shape_1:
param: /mission/identify_dock/shape_1
options: [CIRCLE, TRIANGLE, CROSS, ANY]
description: >
- The shape of the first bay to dock in during the dentify
+ The shape of the first bay to dock in during the identify
Symbols and Dock mission. If set to ANY, mission should dock based on the
color parameter and set this parameter during the mission
dock_color_1:
param: /mission/identify_dock/color_1
options: [RED, GREEN, BLUE, ANY]
description: >
- The color of the first bay to dock in during the dentify Symbols and Dock
+ The color of the first bay to dock in during the identify Symbols and Dock
mission. If set to ANY, mission should dock based on the shape parameter
and set this parameter during the mission
@@ -174,7 +174,7 @@ dock_shape_2:
description: >
# yamllint disable-line rule:line-length
The shape of the second bay to dock in during the
- dentify Symbols and Dock mission. If set to ANY,
+ identify Symbols and Dock mission. If set to ANY,
mission should dock based on the color parameter and set this
parameter during the mission
dock_color_2:
@@ -183,6 +183,6 @@ dock_color_2:
description: >
# yamllint disable-line rule:line-length
The color of the second bay to dock in during the
- dentify Symbols and Dock mission.
+ identify Symbols and Dock mission.
If set to ANY, mission should dock based on the shape
parameter and set this parameter during the mission
diff --git a/NaviGator/mission_control/navigator_missions/navigator_missions/constant_velocity.py b/NaviGator/mission_control/navigator_missions/navigator_missions/constant_velocity.py
index 5ae078c90..a0ce42a26 100644
--- a/NaviGator/mission_control/navigator_missions/navigator_missions/constant_velocity.py
+++ b/NaviGator/mission_control/navigator_missions/navigator_missions/constant_velocity.py
@@ -66,7 +66,7 @@ def decode_parameters(cls, parameters):
return parsed
async def run(self, args):
- # Publish a velocity of zero for a while to stabalize navigator
+ # Publish a velocity of zero for a while to stabilize navigator
self.send_feedback("Switching trajectory to constant")
await self.change_trajectory("constant")
await self.nh.sleep(0.1)
diff --git a/NaviGator/mission_control/navigator_missions/navigator_missions/demonstrate_navigation.py b/NaviGator/mission_control/navigator_missions/navigator_missions/demonstrate_navigation.py
index 6c53d35a4..599a388cc 100644
--- a/NaviGator/mission_control/navigator_missions/navigator_missions/demonstrate_navigation.py
+++ b/NaviGator/mission_control/navigator_missions/navigator_missions/demonstrate_navigation.py
@@ -68,7 +68,7 @@ async def run(self, parameters):
_, closest_reds = await self.get_sorted_objects("red_cylinder", 1)
_, closest_greens = await self.get_sorted_objects("green_cylinder", 1)
- # Rename the totems for their symantic name
+ # Rename the totems for their semantic name
green_close = closest_greens[0]
red_close = closest_reds[0]
@@ -83,7 +83,7 @@ async def run(self, parameters):
_, closest_reds = await self.get_sorted_objects("red_cylinder", 2)
_, closest_greens = await self.get_sorted_objects("green_cylinder", 2)
- # Rename the totems for their symantic name
+ # Rename the totems for their semantic name
green_far = closest_greens[1]
red_far = closest_reds[1]
diff --git a/NaviGator/mission_control/navigator_missions/navigator_missions/detect_deliver_2016.py b/NaviGator/mission_control/navigator_missions/navigator_missions/detect_deliver_2016.py
index 28c3ac4d9..dee540de0 100644
--- a/NaviGator/mission_control/navigator_missions/navigator_missions/detect_deliver_2016.py
+++ b/NaviGator/mission_control/navigator_missions/navigator_missions/detect_deliver_2016.py
@@ -153,9 +153,7 @@ async def do_circle():
await self.nh.sleep(0.25)
continue
fprint(
- "Shape ({}found, using normal to look at other 3 shapes if needed".format(
- res[0],
- ),
+ f"Shape ({res[0]}found, using normal to look at other 3 shapes if needed",
title="DETECT DELIVER",
msg_color="green",
)
diff --git a/NaviGator/mission_control/navigator_missions/navigator_missions/move.py b/NaviGator/mission_control/navigator_missions/navigator_missions/move.py
index 8ae428057..a9debd213 100755
--- a/NaviGator/mission_control/navigator_missions/navigator_missions/move.py
+++ b/NaviGator/mission_control/navigator_missions/navigator_missions/move.py
@@ -149,7 +149,7 @@ async def run(self, args):
"yl": "yaw_left",
"yr": "yaw_right",
}
- command = command if command not in shorthand else shorthand[command]
+ command = shorthand.get(command, command)
movement = getattr(self.move, command)
trans_move = command[:3] != "yaw"
diff --git a/NaviGator/mission_control/navigator_missions/navigator_missions/pose_editor.py b/NaviGator/mission_control/navigator_missions/navigator_missions/pose_editor.py
index 5f25f36ab..d2b1855cd 100644
--- a/NaviGator/mission_control/navigator_missions/navigator_missions/pose_editor.py
+++ b/NaviGator/mission_control/navigator_missions/navigator_missions/pose_editor.py
@@ -341,9 +341,7 @@ def as_MoveGoal(self, move_type=MoveGoal.DRIVE, **kwargs):
for key in kwargs:
if not hasattr(MoveGoal, key):
fprint(
- "MoveGoal msg doesn't have a field called '{}' you tried to set via kwargs.".format(
- key,
- ),
+ f"MoveGoal msg doesn't have a field called '{key}' you tried to set via kwargs.",
title="POSE_EDITOR",
msg_color="red",
)
diff --git a/NaviGator/mission_control/navigator_missions/vrx_missions/dock.py b/NaviGator/mission_control/navigator_missions/vrx_missions/dock.py
index 23d7cdfb3..44a3cacae 100644
--- a/NaviGator/mission_control/navigator_missions/vrx_missions/dock.py
+++ b/NaviGator/mission_control/navigator_missions/vrx_missions/dock.py
@@ -607,7 +607,7 @@ async def prepare_for_docking(self):
# This function looks at the two squares in front of the boat
# and it gets the middle pixel between the two squares.
# If the middle pixel is for some reason not in the middle of our camera...
- # adjust the boat postiion before docking
+ # adjust the boat position before docking
print("prepare for landing!")
img = await self.front_left_camera_sub.get_next_message()
diff --git a/NaviGator/mission_control/navigator_missions/vrx_missions/vrx.py b/NaviGator/mission_control/navigator_missions/vrx_missions/vrx.py
index d629df644..91514c01d 100644
--- a/NaviGator/mission_control/navigator_missions/vrx_missions/vrx.py
+++ b/NaviGator/mission_control/navigator_missions/vrx_missions/vrx.py
@@ -29,145 +29,143 @@
class Vrx(NaviGatorMission):
nh: NodeHandle
- def __init__(self, *args, **kwargs):
- super().__init__(*args, **kwargs)
-
- @staticmethod
- async def init():
- if hasattr(Vrx, "_vrx_init"):
+ @classmethod
+ async def setup(cls):
+ if hasattr(cls, "_cls_init"):
return
- Vrx.from_lla = Vrx.nh.get_service_client("/fromLL", FromLL)
- Vrx.to_lla = Vrx.nh.get_service_client("/toLL", ToLL)
- Vrx.task_info_sub = Vrx.nh.subscribe("/vrx/task/info", Task)
- await Vrx.task_info_sub.setup()
- Vrx.scan_dock_color_sequence = Vrx.nh.get_service_client(
+ cls.from_lla = cls.nh.get_service_client("/fromLL", FromLL)
+ cls.to_lla = cls.nh.get_service_client("/toLL", ToLL)
+ cls.task_info_sub = cls.nh.subscribe("/vrx/task/info", Task)
+ cls.scan_dock_color_sequence = cls.nh.get_service_client(
"/vrx/scan_dock_deliver/color_sequence",
ColorSequence,
)
- Vrx.fire_ball = Vrx.nh.advertise("/wamv/shooters/ball_shooter/fire", Empty)
- Vrx.station_keep_goal = Vrx.nh.subscribe(
+ cls.fire_ball = cls.nh.advertise("/wamv/shooters/ball_shooter/fire", Empty)
+ cls.station_keep_goal = cls.nh.subscribe(
"/vrx/station_keeping/goal",
GeoPoseStamped,
)
- Vrx.wayfinding_path_sub = Vrx.nh.subscribe("/vrx/wayfinding/waypoints", GeoPath)
- Vrx.station_keeping_pose_error = Vrx.nh.subscribe(
+ cls.wayfinding_path_sub = cls.nh.subscribe("/vrx/wayfinding/waypoints", GeoPath)
+ cls.station_keeping_pose_error = cls.nh.subscribe(
"/vrx/station_keeping/pose_error",
Float64,
)
- Vrx.station_keeping_rms_error = Vrx.nh.subscribe(
+ cls.station_keeping_rms_error = cls.nh.subscribe(
"/vrx/station_keeping/rms_error",
Float64,
)
- Vrx.wayfinding_min_errors = Vrx.nh.subscribe(
+ cls.wayfinding_min_errors = cls.nh.subscribe(
"/vrx/wayfinding/min_errors",
Float64MultiArray,
)
- Vrx.wayfinding_mean_error = Vrx.nh.subscribe(
+ cls.wayfinding_mean_error = cls.nh.subscribe(
"/vrx/wayfinding/mean_error",
Float64,
)
- Vrx.perception_landmark = Vrx.nh.advertise(
+ cls.perception_landmark = cls.nh.advertise(
"/vrx/perception/landmark",
GeoPoseStamped,
)
await asyncio.gather(
- Vrx.fire_ball.setup(),
- Vrx.station_keep_goal.setup(),
- Vrx.wayfinding_path_sub.setup(),
- Vrx.station_keeping_pose_error.setup(),
- Vrx.station_keeping_rms_error.setup(),
- Vrx.wayfinding_min_errors.setup(),
- Vrx.wayfinding_mean_error.setup(),
- Vrx.perception_landmark.setup(),
+ cls.task_info_sub.setup(),
+ cls.fire_ball.setup(),
+ cls.station_keep_goal.setup(),
+ cls.wayfinding_path_sub.setup(),
+ cls.station_keeping_pose_error.setup(),
+ cls.station_keeping_rms_error.setup(),
+ cls.wayfinding_min_errors.setup(),
+ cls.wayfinding_mean_error.setup(),
+ cls.perception_landmark.setup(),
)
- Vrx.animal_landmarks = Vrx.nh.subscribe("/vrx/wildlife/animals/poses", GeoPath)
- Vrx.beacon_landmark = Vrx.nh.get_service_client("beaconLocator", AcousticBeacon)
- Vrx.circle_animal = Vrx.nh.get_service_client("/choose_animal", ChooseAnimal)
- Vrx.set_long_waypoint = Vrx.nh.get_service_client(
+ cls.animal_landmarks = cls.nh.subscribe("/vrx/wildlife/animals/poses", GeoPath)
+ cls.beacon_landmark = cls.nh.get_service_client("beaconLocator", AcousticBeacon)
+ cls.circle_animal = cls.nh.get_service_client("/choose_animal", ChooseAnimal)
+ cls.set_long_waypoint = cls.nh.get_service_client(
"/set_long_waypoint",
MoveToWaypoint,
)
- Vrx.yolo_objects = Vrx.nh.subscribe("/yolov7/detections", Detection2DArray)
- Vrx.tf_listener = axros_tf.TransformListener(Vrx.nh)
- await Vrx.tf_listener.setup()
- Vrx.database_response = Vrx.nh.get_service_client(
+ cls.yolo_objects = cls.nh.subscribe("/yolov7/detections", Detection2DArray)
+ cls.tf_listener = axros_tf.TransformListener(cls.nh)
+ await cls.tf_listener.setup()
+ cls.database_response = cls.nh.get_service_client(
"/database/requests",
ObjectDBQuery,
)
- Vrx.get_two_closest_cones = Vrx.nh.get_service_client(
+ cls.get_two_closest_cones = cls.nh.get_service_client(
"/get_two_closest_cones",
TwoClosestCones,
)
await asyncio.gather(
- Vrx.animal_landmarks.setup(),
- Vrx.yolo_objects.setup(),
+ cls.animal_landmarks.setup(),
+ cls.yolo_objects.setup(),
)
- Vrx.pcodar_reset = Vrx.nh.get_service_client("/pcodar/reset", Trigger)
+ cls.pcodar_reset = cls.nh.get_service_client("/pcodar/reset", Trigger)
- Vrx.front_left_camera_info_sub = None
- Vrx.front_left_camera_sub = None
- Vrx.front_right_camera_info_sub = None
- Vrx.front_right_camera_sub = None
+ cls.front_left_camera_info_sub = None
+ cls.front_left_camera_sub = None
+ cls.front_right_camera_info_sub = None
+ cls.front_right_camera_sub = None
- Vrx._vrx_init = True
+ cls._cls_init = True
- @staticmethod
- async def shutdown():
+ @classmethod
+ async def shutdown(cls):
+ return
await asyncio.gather(
- Vrx.task_info_sub.shutdown(),
- Vrx.animal_landmarks.shutdown(),
- Vrx.yolo_objects.shutdown(),
- Vrx.fire_ball.shutdown(),
- Vrx.station_keep_goal.shutdown(),
- Vrx.wayfinding_path_sub.shutdown(),
- Vrx.station_keeping_pose_error.shutdown(),
- Vrx.station_keeping_rms_error.shutdown(),
- Vrx.wayfinding_min_errors.shutdown(),
- Vrx.wayfinding_mean_error.shutdown(),
- Vrx.perception_landmark.shutdown(),
+ cls.task_info_sub.shutdown(),
+ cls.animal_landmarks.shutdown(),
+ cls.yolo_objects.shutdown(),
+ cls.fire_ball.shutdown(),
+ cls.station_keep_goal.shutdown(),
+ cls.wayfinding_path_sub.shutdown(),
+ cls.station_keeping_pose_error.shutdown(),
+ cls.station_keeping_rms_error.shutdown(),
+ cls.wayfinding_min_errors.shutdown(),
+ cls.wayfinding_mean_error.shutdown(),
+ cls.perception_landmark.shutdown(),
)
def cleanup(self):
pass
- @staticmethod
- async def init_front_left_camera():
- if Vrx.front_left_camera_sub is None:
- Vrx.front_left_camera_sub = Vrx.nh.subscribe(
+ @classmethod
+ async def init_front_left_camera(cls):
+ if cls.front_left_camera_sub is None:
+ cls.front_left_camera_sub = cls.nh.subscribe(
"/wamv/sensors/cameras/front_left_camera/image_raw",
Image,
)
- if Vrx.front_left_camera_info_sub is None:
- Vrx.front_left_camera_info_sub = Vrx.nh.subscribe(
+ if cls.front_left_camera_info_sub is None:
+ cls.front_left_camera_info_sub = cls.nh.subscribe(
"/wamv/sensors/cameras/front_left_camera/camera_info",
CameraInfo,
)
await asyncio.gather(
- Vrx.front_left_camera_sub.setup(),
- Vrx.front_left_camera_info_sub.setup(),
+ cls.front_left_camera_sub.setup(),
+ cls.front_left_camera_info_sub.setup(),
)
- @staticmethod
- async def init_front_right_camera():
- if Vrx.front_right_camera_sub is None:
- Vrx.front_right_camera_sub = Vrx.nh.subscribe(
+ @classmethod
+ async def init_front_right_camera(cls):
+ if cls.front_right_camera_sub is None:
+ cls.front_right_camera_sub = cls.nh.subscribe(
"/wamv/sensors/cameras/front_right_camera/image_raw",
Image,
)
- if Vrx.front_right_camera_info_sub is None:
- Vrx.front_right_camera_info_sub = Vrx.nh.subscribe(
+ if cls.front_right_camera_info_sub is None:
+ cls.front_right_camera_info_sub = cls.nh.subscribe(
"/wamv/sensors/cameras/front_right_camera/camera_info",
CameraInfo,
)
await asyncio.gather(
- Vrx.front_right_camera_sub.setup(),
- Vrx.front_right_camera_info_sub.setup(),
+ cls.front_right_camera_sub.setup(),
+ cls.front_right_camera_info_sub.setup(),
)
async def geo_pose_to_enu_pose(self, geo):
diff --git a/NaviGator/mission_control/navigator_missions/vrx_missions/vrx_wayfinding_2.py b/NaviGator/mission_control/navigator_missions/vrx_missions/vrx_wayfinding_2.py
index 60496d0b8..966f38be0 100644
--- a/NaviGator/mission_control/navigator_missions/vrx_missions/vrx_wayfinding_2.py
+++ b/NaviGator/mission_control/navigator_missions/vrx_missions/vrx_wayfinding_2.py
@@ -5,6 +5,7 @@
from .vrx import Vrx
___author___ = "Alex Perez"
+# Optimized by Daniel Parra
class VrxWayfinding2(Vrx):
@@ -42,12 +43,18 @@ async def run(self, parameters):
poses = poses[:start_pose_index]
path = path[1:]
- # self.send_feedback('Sorted poses' + str(poses))
await self.wait_for_task_such_that(lambda task: task.state in ["running"])
# do movements
for index in path:
self.send_feedback(f"Going to {poses[index]}")
-
# Go to goal
+ P = 0.85
+ part_way_point = [x * P for x in poses[index][0][:-1]]
+ part_way_point.append(poses[index][0][-1])
+ self.send_feedback(
+ f"\nPartway:\n{part_way_point}\nEndPoint:\n{poses[index][0]}",
+ )
+
+ await self.send_trajectory_without_path([part_way_point, poses[index][1]])
await self.send_trajectory_without_path(poses[index])
diff --git a/NaviGator/satellite/rviz_satellite/src/aerialmap_display.cpp b/NaviGator/satellite/rviz_satellite/src/aerialmap_display.cpp
index 22a307f76..bf5ec8b20 100644
--- a/NaviGator/satellite/rviz_satellite/src/aerialmap_display.cpp
+++ b/NaviGator/satellite/rviz_satellite/src/aerialmap_display.cpp
@@ -416,7 +416,7 @@ void AerialMapDisplay::assembleScene()
// determine location of this tile, flipping y in the process
const double x = (tile.x() - loader_->centerTileX()) * tile_w + origin_x;
const double y = -(tile.y() - loader_->centerTileY()) * tile_h + origin_y;
- // don't re-use any ids
+ // don't reuse any ids
const std::string name_suffix = std::to_string(tile.x()) + "_" + std::to_string(tile.y()) + "_" +
std::to_string(map_id_) + "_" + std::to_string(scene_id_);
diff --git a/NaviGator/scripts/bash_aliases.sh b/NaviGator/scripts/bash_aliases.sh
index 216b1ff80..de6da5f4b 100755
--- a/NaviGator/scripts/bash_aliases.sh
+++ b/NaviGator/scripts/bash_aliases.sh
@@ -18,7 +18,7 @@ nthrust() {
topic="/$1_motor/cmd"
publishers=$(rostopic info "$topic" | grep Publishers)
if [ "$publishers" != "Publishers: None" ]; then
- echo "Somone is already publishing to $topic. Perhaps you need to kill thrust mapper?"
+ echo "Someone is already publishing to $topic. Perhaps you need to kill thrust mapper?"
return 1
fi
rostopic pub "$topic" "roboteq_msgs/Command" "setpoint: $2" -r100
diff --git a/NaviGator/utils/navigator_msgs/srv/GetDockBays.srv b/NaviGator/utils/navigator_msgs/srv/GetDockBays.srv
index 9a39764bd..7081b1b07 100644
--- a/NaviGator/utils/navigator_msgs/srv/GetDockBays.srv
+++ b/NaviGator/utils/navigator_msgs/srv/GetDockBays.srv
@@ -2,4 +2,4 @@
geometry_msgs/Point[3] bays #The positions in ENU frame of the center of the three bays 0=left, 1=center, 2=right
geometry_msgs/Vector3 normal #Vector or normal pointing away from plane of dock back
bool success #False if an error occurred getting dock bays
-string error #Descripion of error if success=false
+string error #Description of error if success=false
diff --git a/NaviGator/utils/navigator_tools/nodes/navigator_status_tui b/NaviGator/utils/navigator_tools/nodes/navigator_status_tui
index 3efa0a5d1..0fc39eb3b 100755
--- a/NaviGator/utils/navigator_tools/nodes/navigator_status_tui
+++ b/NaviGator/utils/navigator_tools/nodes/navigator_status_tui
@@ -35,7 +35,7 @@ class nav_tui:
self.panel.hide()
panel.update_panels()
self.rate = rospy.Rate(2) # Fixed rate for while loop to update at: 2 hz
- # The following are default field initalizations for various values that that will be overwritten
+ # The following are default field initializations for various values that that will be overwritten
self.voltage = 0
self.wrench = None
self.LAT = None
@@ -214,15 +214,13 @@ class nav_tui:
if len(self.decode_fault_status(self.FL_fault)) == 0:
self.window.addstr(5, self.x / 2 - 7, "No faults", curses.color_pair(3))
else:
- n = 0
- for fault in self.decode_fault_status(self.FL_fault):
+ for n, fault in enumerate(self.decode_fault_status(self.FL_fault)):
self.window.addstr(
5 + n,
self.x / 2 - 7,
"%s" % fault,
curses.color_pair(1),
)
- n += 1
self.window.addstr(14, self.x / 2 - 7, "Back Left", color)
if len(self.decode_fault_status(self.BL_fault)) == 0:
diff --git a/NaviGator/utils/remote_control/navigator_emergency_control/nodes/navigator_emergency.py b/NaviGator/utils/remote_control/navigator_emergency_control/nodes/navigator_emergency.py
index cb3354580..49b799fa4 100755
--- a/NaviGator/utils/remote_control/navigator_emergency_control/nodes/navigator_emergency.py
+++ b/NaviGator/utils/remote_control/navigator_emergency_control/nodes/navigator_emergency.py
@@ -94,7 +94,7 @@ def check_for_timeout(self, joy: Joy):
def joy_recieved(self, joy: Joy) -> None:
"""
- Button elements are being assigned and simplied to readable names. The
+ Button elements are being assigned and simplified to readable names. The
number of deployments or retractions for thrusters are being updated based
on several conditions. Moreover, additional settings are changed based on the
state of the controller and the activation of potential alarms or switches.
diff --git a/NaviGator/utils/voltage_gui/src/voltage_gui.py b/NaviGator/utils/voltage_gui/src/voltage_gui.py
index 932dbc22b..79e6a0e85 100644
--- a/NaviGator/utils/voltage_gui/src/voltage_gui.py
+++ b/NaviGator/utils/voltage_gui/src/voltage_gui.py
@@ -184,7 +184,7 @@ def resizeFont(self) -> None: # done
threshFont = QtGui.QFont("Times", (self.fontSize) / 3, QtGui.QFont.Bold)
self.labelThresh.setFont(threshFont)
- # Sets the text of the thrshold info box
+ # Sets the text of the threshold info box
def initThresh(self) -> None:
"""
Sets the text of the threshold info box
diff --git a/SubjuGator/command/subjugator_launch/config/passive_sonar.yaml b/SubjuGator/command/subjugator_launch/config/passive_sonar.yaml
index 9901f9703..e55aec3da 100644
--- a/SubjuGator/command/subjugator_launch/config/passive_sonar.yaml
+++ b/SubjuGator/command/subjugator_launch/config/passive_sonar.yaml
@@ -3,7 +3,7 @@
dist_h: 2.286e-02
# speed of sound in water
v_sound: 1482
-# target Frquency in Hz
+# target Frequency in Hz
triggering/target_frequency: 30000
# tolerance around target frequerncy in Hz
triggering/frequency_tolerance: 100
diff --git a/SubjuGator/command/subjugator_launch/launch/subsystems/nav_box.launch b/SubjuGator/command/subjugator_launch/launch/subsystems/nav_box.launch
index eb5e1bc31..3dee6ee81 100644
--- a/SubjuGator/command/subjugator_launch/launch/subsystems/nav_box.launch
+++ b/SubjuGator/command/subjugator_launch/launch/subsystems/nav_box.launch
@@ -42,10 +42,10 @@
scale:
- - [0.993770963897068, 0.00105871125374563, 7.659410525291767e-05]
- - [0.00105871125374563, 0.9996814868251349, -0.0011040738267441828]
- - [7.659410525291767e-05, -0.001104073826744163, 1.0065910531028952]
- shift: [1.2551999807772446e-06, -1.1666595150804588e-06, 6.895773090438596e-08]
+ - [0.9991765357958566, 0.006242798579443988, -0.008472478269327878]
+ - [0.006242798579443957, 1.0016179705091928, 0.0059841151097914345]
+ - [-0.008472478269327836, 0.0059841151097913, 0.999354597532967]
+ shift: [7.889247409445414e-06, 4.879179471165382e-06, 7.46017199298374e-06]
diff --git a/SubjuGator/drivers/magnetic_compensation/sub8_magnetic_hardsoft_compensation/scripts/generate_config b/SubjuGator/drivers/magnetic_compensation/sub8_magnetic_hardsoft_compensation/scripts/generate_config
index f818bd613..342292350 100755
--- a/SubjuGator/drivers/magnetic_compensation/sub8_magnetic_hardsoft_compensation/scripts/generate_config
+++ b/SubjuGator/drivers/magnetic_compensation/sub8_magnetic_hardsoft_compensation/scripts/generate_config
@@ -9,6 +9,7 @@ import rosbag
import roslib
import scipy.linalg
import yaml
+from mpl_toolkits.mplot3d import Axes3D
from tf import transformations
roslib.load_manifest("magnetic_hardsoft_compensation")
@@ -20,7 +21,7 @@ def normalized_matrix(m):
def calculate_error(points):
- radii = map(numpy.linalg.norm, points)
+ radii = list(map(numpy.linalg.norm, points))
error = numpy.std(radii) / numpy.mean(radii)
return error
@@ -47,7 +48,7 @@ def fit_ellipsoid(points):
B = numpy.ones((points.shape[0], 1))
- X = numpy.linalg.lstsq(A, B)[0].flatten()
+ X = numpy.linalg.lstsq(A, B, rcond=-1)[0].flatten()
if X[0] < 0:
X = -X # make sure ka turns out positive definite
@@ -131,9 +132,11 @@ if __name__ == "__main__":
with rosbag.Bag(sys.argv[1]) as bag:
points = numpy.array(
[
- mil_ros_tools.rosmsg_to_numpy(msg.magnetic_field)
- if hasattr(msg, "magnetic_field")
- else mil_ros_tools.rosmsg_to_numpy(msg.vector)
+ (
+ mil_ros_tools.rosmsg_to_numpy(msg.magnetic_field)
+ if hasattr(msg, "magnetic_field")
+ else mil_ros_tools.rosmsg_to_numpy(msg.vector)
+ )
for topic, msg, t in bag.read_messages(topics=["/imu/mag_raw"])
],
)
@@ -150,7 +153,7 @@ if __name__ == "__main__":
import matplotlib.pyplot as plt
fig = plt.figure(figsize=(10, 10))
- ax = fig.add_subplot("111", projection="3d")
+ ax = Axes3D(fig)
ax.scatter([0], [0], [0], s=100, c="r")
ax.scatter(*zip(*points[::10, :]))
axisEqual3D(ax)
@@ -168,7 +171,7 @@ if __name__ == "__main__":
import matplotlib.pyplot as plt
fig = plt.figure(figsize=(10, 10))
- ax = fig.add_subplot("111", projection="3d")
+ ax = Axes3D(fig)
ax.scatter([0], [0], [0], s=100, c="r")
ax.scatter(*zip(*points[::10, :]))
ax.scatter(*zip(*compensated[::10, :]), c="g")
@@ -183,8 +186,8 @@ if __name__ == "__main__":
print(
yaml.dump(
{
- "scale": (map(float, x) for x in scale),
- "shift": map(float, shift),
+ "scale": scale.tolist(),
+ "shift": shift.tolist(),
},
),
)
diff --git a/SubjuGator/drivers/sub8_thrust_and_kill_board/sub8_thrust_and_kill_board/simulation.py b/SubjuGator/drivers/sub8_thrust_and_kill_board/sub8_thrust_and_kill_board/simulation.py
index 5f9d0f01f..83c595815 100644
--- a/SubjuGator/drivers/sub8_thrust_and_kill_board/sub8_thrust_and_kill_board/simulation.py
+++ b/SubjuGator/drivers/sub8_thrust_and_kill_board/sub8_thrust_and_kill_board/simulation.py
@@ -156,4 +156,4 @@ def on_data(self, data: bytes, can_id: int) -> None:
packet = HeartbeatMessage.from_bytes(data)
self._last_heartbeat = rospy.Time.now()
else:
- assert False, "No recognized identifier"
+ raise Exception("No recognized identifier")
diff --git a/SubjuGator/etc/motd b/SubjuGator/etc/motd
new file mode 100644
index 000000000..bf6bb0855
--- /dev/null
+++ b/SubjuGator/etc/motd
@@ -0,0 +1,9 @@
+#-------#-------#-------#-------#-------#-------#-------#-------#
+ You have connected to SubjuGator 8!
+#-------#-------#-------#-------#-------#-------#-------#-------#
+
+If you are testing the sub in the water (or are preparing to do so), please make sure to read the Subjugator Testing Procedures page on uf-mil.github.io for useful tips, advice, and checklists.
+
+We (the previous MIL members) will watch your testing session with great interest.
+
+Happy Testing!
diff --git a/SubjuGator/perception/subjugator_perception/nodes/dice_detect.py b/SubjuGator/perception/subjugator_perception/nodes/dice_detect.py
index 55d1dd5e2..312123597 100755
--- a/SubjuGator/perception/subjugator_perception/nodes/dice_detect.py
+++ b/SubjuGator/perception/subjugator_perception/nodes/dice_detect.py
@@ -93,7 +93,7 @@ def detect(self, dice_img):
params.minConvexity = 0.8 # 1 = perfect convex hull
# Filter by Inertia
params.filterByInertia = True
- params.minInertiaRatio = 0.4 # Defines the ellipsoid 1= detects only cirlces
+ params.minInertiaRatio = 0.4 # Defines the ellipsoid 1= detects only circles
# 0 = Detects even lines
# Create a detector with the parameters
diff --git a/SubjuGator/perception/subjugator_perception/nodes/hsv_calibration.py b/SubjuGator/perception/subjugator_perception/nodes/hsv_calibration.py
index 4a67f4bb7..433133431 100755
--- a/SubjuGator/perception/subjugator_perception/nodes/hsv_calibration.py
+++ b/SubjuGator/perception/subjugator_perception/nodes/hsv_calibration.py
@@ -36,13 +36,17 @@ def parse_string(threshes):
def reconfigure(self, config, level):
try:
self.lower = np.array(self.parse_string(config["dyn_lower"]))
- rospy.logwarn("HSV lower bound below minimum value") if (
- self.lower < 0
- ).any() else None
+ (
+ rospy.logwarn("HSV lower bound below minimum value")
+ if (self.lower < 0).any()
+ else None
+ )
self.upper = np.array(self.parse_string(config["dyn_upper"]))
- rospy.logwarn("HSV upper bound above maximum values") if (
- self.upper[0] > 179
- ).any() or (self.upper[1:] > 255).any() else None
+ (
+ rospy.logwarn("HSV upper bound above maximum values")
+ if (self.upper[0] > 179).any() or (self.upper[1:] > 255).any()
+ else None
+ )
except ValueError as e:
rospy.logwarn(f"Invalid dynamic reconfigure: {e}")
diff --git a/SubjuGator/perception/subjugator_perception/nodes/orange_rectangle_finder.py b/SubjuGator/perception/subjugator_perception/nodes/orange_rectangle_finder.py
index 0701c3b05..237fe94e3 100755
--- a/SubjuGator/perception/subjugator_perception/nodes/orange_rectangle_finder.py
+++ b/SubjuGator/perception/subjugator_perception/nodes/orange_rectangle_finder.py
@@ -52,7 +52,7 @@ class OrangeRectangleFinder:
* Transform this frames pose into /map frame
* Plug this frames pose in /map into a kalman filter to reduce noise
- TODO: Allow for two objects to be identifed at once, both filtered through its own KF
+ TODO: Allow for two objects to be identified at once, both filtered through its own KF
"""
# Coordinate axes for debugging image
diff --git a/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/HOG/HOG_SVM_trainer.py b/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/HOG/HOG_SVM_trainer.py
index bbdb7aefb..01e85b3a2 100644
--- a/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/HOG/HOG_SVM_trainer.py
+++ b/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/HOG/HOG_SVM_trainer.py
@@ -16,8 +16,7 @@
class_list = np.array(0)
# loop through the training images
-count = 0
-for i in os.listdir(os.path.abspath(folder)):
+for count, i in enumerate(os.listdir(os.path.abspath(folder))):
# get the roi from the file
path = folder + "/" + i
roi_str = f.readline()
@@ -72,7 +71,6 @@
class_temp = np.empty(len_myinvhog / 9)
class_temp.fill(-1)
class_list = np.append(class_list, class_temp)
- count += 1
# hack
class_list = np.delete(class_list, [0])
diff --git a/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/machine_learning/boost_auto.py b/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/machine_learning/boost_auto.py
index c9027ff60..c1cf17e1a 100644
--- a/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/machine_learning/boost_auto.py
+++ b/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/machine_learning/boost_auto.py
@@ -100,10 +100,11 @@ def train_on_data(observation_list, label_list, split_factor=4):
s_time = time.time()
process_round = 0
# Split this into multiple passes in an attempt to free RAM (no idea if this works).
- for x, y in zip(all_observations_split, all_labels_split):
+ for process_round, (x, y) in enumerate(
+ zip(all_observations_split, all_labels_split),
+ ):
print(f"Training subset {process_round + 1}/{split_factor}.")
boost.train(x, cv2.CV_ROW_SAMPLE, y, params=parameters)
- process_round += 1
print(f"Time to complete: {time.time() - s_time}")
print("Done! Saving...")
diff --git a/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/marker_occ_grid.py b/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/marker_occ_grid.py
index 9261de0ac..c547f7847 100644
--- a/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/marker_occ_grid.py
+++ b/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/marker_occ_grid.py
@@ -174,7 +174,7 @@ def return_pose(self, srv):
self.poly_generator = self.polygon_generator()
return [0, False, srv.intial_position]
- # We search at 1.5 * r so that there is some overlay in the search feilds.
+ # We search at 1.5 * r so that there is some overlay in the search fields.
np_pose = msg_helpers.pose_to_numpy(srv.intial_position)
rot_mat = make_2D_rotation(
tf.transformations.euler_from_quaternion(np_pose[1])[2],
@@ -249,7 +249,6 @@ def polygon_generator(self, n=12):
class MarkerOccGrid(OccGridUtils):
-
"""
Handles updating occupancy grid when new data comes in.
TODO: Upon call can return some path to go to in order to find them.
diff --git a/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/rviz.py b/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/rviz.py
index c46dd18ea..e6af8929a 100644
--- a/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/rviz.py
+++ b/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/rviz.py
@@ -9,7 +9,6 @@
class RvizVisualizer:
-
"""Cute tool for drawing both depth and height-from-bottom in RVIZ"""
def __init__(self, topic="visualization/markers"):
diff --git a/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/visual_threshold_tools.py b/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/visual_threshold_tools.py
index 7ec7d04c9..f30275cfc 100644
--- a/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/visual_threshold_tools.py
+++ b/SubjuGator/perception/subjugator_perception/subjugator_vision_tools/visual_threshold_tools.py
@@ -63,7 +63,6 @@ def denormalize(val, _min, _max):
class ExtentDialog(traits.api.HasTraits):
-
"""A dialog to graphically adjust the extents of a threshold range"""
# Data extents
diff --git a/SubjuGator/perception/subjugator_perception/test/test_path_marker.py b/SubjuGator/perception/subjugator_perception/test/test_path_marker.py
index 4f3a621cc..5674ddf5a 100755
--- a/SubjuGator/perception/subjugator_perception/test/test_path_marker.py
+++ b/SubjuGator/perception/subjugator_perception/test/test_path_marker.py
@@ -17,7 +17,6 @@
class TestPathMarker(unittest.TestCase):
-
"""
Unit test for perception service finding orange path markers
Plays several bags with known pixel coordinates of path marker,
diff --git a/SubjuGator/simulation/subjugator_gazebo/diagnostics/gazebo_tests/common.py b/SubjuGator/simulation/subjugator_gazebo/diagnostics/gazebo_tests/common.py
index de7bc39f0..38a5baf41 100644
--- a/SubjuGator/simulation/subjugator_gazebo/diagnostics/gazebo_tests/common.py
+++ b/SubjuGator/simulation/subjugator_gazebo/diagnostics/gazebo_tests/common.py
@@ -8,7 +8,6 @@
class Job:
-
"""Inherit from this!"""
_job_name = "generic job"
diff --git a/SubjuGator/simulation/subjugator_gazebo/urdf/sub8.urdf.xacro b/SubjuGator/simulation/subjugator_gazebo/urdf/sub8.urdf.xacro
index 9290884dd..3f4517335 100644
--- a/SubjuGator/simulation/subjugator_gazebo/urdf/sub8.urdf.xacro
+++ b/SubjuGator/simulation/subjugator_gazebo/urdf/sub8.urdf.xacro
@@ -11,8 +11,6 @@
-
-
@@ -33,11 +31,6 @@
-
-
-
-
-
diff --git a/SubjuGator/simulation/subjugator_simulation/subjugator_sim_tools/shaders/shader_manager.py b/SubjuGator/simulation/subjugator_simulation/subjugator_sim_tools/shaders/shader_manager.py
index edfb7d12f..192755207 100644
--- a/SubjuGator/simulation/subjugator_simulation/subjugator_sim_tools/shaders/shader_manager.py
+++ b/SubjuGator/simulation/subjugator_simulation/subjugator_sim_tools/shaders/shader_manager.py
@@ -36,7 +36,6 @@ def add_item(self, position, intensity):
class ShaderManager:
-
"""
This class is used when you want to have an entity switch out shaders at a specific time.
If you want to add another rule for when to switch out shaders:
diff --git a/SubjuGator/simulation/subjugator_simulation/subjugator_sim_tools/shaders/shaders.py b/SubjuGator/simulation/subjugator_simulation/subjugator_sim_tools/shaders/shaders.py
index d4a2e1f62..210a68e8e 100644
--- a/SubjuGator/simulation/subjugator_simulation/subjugator_sim_tools/shaders/shaders.py
+++ b/SubjuGator/simulation/subjugator_simulation/subjugator_sim_tools/shaders/shaders.py
@@ -65,7 +65,6 @@ def recursive_dictionary(self, path, text):
class Shaders:
-
"""A Shaders class, which automatically contains all of the shaders
in the shaders folder
WTF?
diff --git a/SubjuGator/simulation/subjugator_simulation/subjugator_sim_tools/widgets/sub.py b/SubjuGator/simulation/subjugator_simulation/subjugator_sim_tools/widgets/sub.py
index cbb628bad..144ec195d 100644
--- a/SubjuGator/simulation/subjugator_simulation/subjugator_sim_tools/widgets/sub.py
+++ b/SubjuGator/simulation/subjugator_simulation/subjugator_sim_tools/widgets/sub.py
@@ -83,7 +83,6 @@ def make_visual(self, physical, position, thrust_indicators=False):
)
class ThrustGetter:
-
"""This is a pretty garbage thing, and will be replaced by the scenegraph system"""
def __init__(self, thruster_name, rdir):
diff --git a/SubjuGator/utils/subjugator_diagnostics/scripts/self_check.py b/SubjuGator/utils/subjugator_diagnostics/scripts/self_check.py
index 2552541cc..4db32b96c 100755
--- a/SubjuGator/utils/subjugator_diagnostics/scripts/self_check.py
+++ b/SubjuGator/utils/subjugator_diagnostics/scripts/self_check.py
@@ -18,7 +18,6 @@
class TemplateChecker:
-
"""Template for how each checker class should look.
This provides interface functions for the main function to use. You don't have to
implement them all in each checker.
diff --git a/docs/design/passive_sonar/passive_sonar.rst b/docs/design/passive_sonar/passive_sonar.rst
index 522368705..6f23f38ab 100644
--- a/docs/design/passive_sonar/passive_sonar.rst
+++ b/docs/design/passive_sonar/passive_sonar.rst
@@ -78,8 +78,8 @@ Configuration
*************
All parameters that are expected to be changed in tuining are ROS Params initialized in ``passive_sonar.yaml``
-To make a custom configation
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+To make a custom configuration
+^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
* ``roscd subjugator_launch``
diff --git a/docs/electrical/onboarding.md b/docs/electrical/onboarding.md
index c48026aaa..45d73e7a7 100644
--- a/docs/electrical/onboarding.md
+++ b/docs/electrical/onboarding.md
@@ -20,7 +20,7 @@ including meeting times.
## Join the electrical GitHub
Unlike the software and mechanical teams (who share a GitHub repository), we use
-a separate repository for the electrical team. As a resut, you will need to be added
+a separate repository for the electrical team. As a result, you will need to be added
to this organization. Once you're in Slack (or you've come to the lab), ask an electrical
leader to add you to the GitHub organization. The organization can be found [here](https://github.com/uf-mil-electrical).
diff --git a/docs/extensions/attributetable.py b/docs/extensions/attributetable.py
index bfee064d7..53372cb61 100644
--- a/docs/extensions/attributetable.py
+++ b/docs/extensions/attributetable.py
@@ -2,6 +2,7 @@
Credit goes to discord.py and its creators for creating most of this file:
https://github.com/Rapptz/discord.py/blob/master/docs/extensions/attributetable.py
"""
+
import importlib
import inspect
import re
diff --git a/docs/extensions/builder.py b/docs/extensions/builder.py
index 84de6d59d..881417afc 100644
--- a/docs/extensions/builder.py
+++ b/docs/extensions/builder.py
@@ -2,6 +2,7 @@
Credit goes to discord.py and its creators for creating most of this file:
https://github.com/Rapptz/discord.py/blob/master/docs/extensions/attributetable.py
"""
+
from sphinx.builders.html import StandaloneHTMLBuilder
from sphinx.environment.adapters.indexentries import IndexEntries
from sphinx.writers.html5 import HTML5Translator
diff --git a/docs/indyav/software/planning/indyav_path/path_recorder.rst b/docs/indyav/software/planning/indyav_path/path_recorder.rst
index 77c3d4ee3..d1b5f1a47 100644
--- a/docs/indyav/software/planning/indyav_path/path_recorder.rst
+++ b/docs/indyav/software/planning/indyav_path/path_recorder.rst
@@ -33,7 +33,7 @@ Basic Usage Example
- Visualize this new topic in rviz by clicking `Add` and then `/odom2 -> Odometry`
-- Watch the red arrow advance from where the sub started to where the sub stopped updting approximately 10 times a second.
+- Watch the red arrow advance from where the sub started to where the sub stopped updating approximately 10 times a second.
Source Files
^^^^^^^^^^^^
diff --git a/docs/navigator/lessons22.md b/docs/navigator/lessons22.md
index 1c92fc298..25607540e 100644
--- a/docs/navigator/lessons22.md
+++ b/docs/navigator/lessons22.md
@@ -62,7 +62,7 @@ future teams to learn from!
It is quicker to tell when tools have gone missing (as each tool now has a
dedicated spot in the organizer), and which tool is missing. Furthermore, it
becomes easier for software members, electrical members, and mentors to find
- tools, even if they maybe are not acquianted with a deep knowledge of the
+ tools, even if they maybe are not acquainted with a deep knowledge of the
mechanical team.
* **Focus on bringing less and staying more organized.** - At RobotX 2022, we
were one of the teams who had brought the most equipment, yet we had a hard
diff --git a/docs/software/adding_documentation.md b/docs/software/adding_documentation.md
index cc1a1fd46..d91bf76e3 100644
--- a/docs/software/adding_documentation.md
+++ b/docs/software/adding_documentation.md
@@ -100,5 +100,5 @@ $ ./scripts/build_docs --scratch
```
## Contributing changes
-Now that you have made and verifed your changes, follow the [contributing guide](contributing)
+Now that you have made and verified your changes, follow the [contributing guide](contributing)
to add your changes to the repository.
diff --git a/docs/software/getting_started.md b/docs/software/getting_started.md
index 6e94e1653..a40845665 100644
--- a/docs/software/getting_started.md
+++ b/docs/software/getting_started.md
@@ -63,8 +63,8 @@ methods.
| Architecture | URL |
| ------------ | --- |
-| AMD64 (most Windows computers, Intel-based Mac computers) | [focal-desktop-amd64.iso](https://cdimage.ubuntu.com/focal/daily-live/current/focal-desktop-amd64.iso) |
-| ARM64 (Apple Silicon Mac computers) | [focal-desktop-arm64.iso](https://cdimage.ubuntu.com/focal/daily-live/current/focal-desktop-arm64.iso) |
+| AMD64 (most Windows computers, Intel-based Mac computers) | [focal-desktop-amd64.iso](https://releases.ubuntu.com/focal/ubuntu-20.04.6-desktop-amd64.iso) |
+| ARM64 (Apple Silicon Mac computers) | Unfortunately, Ubuntu 20.04 no longer has an ARM-compatible ISO. While we are working on finding/building a new iso image, you may not be able to install. |
The following subsections cover various installation methods. Please choose the
installation option that best meets your use case. If you're not sure what the
@@ -420,7 +420,7 @@ launches the Gazebo GUI - aka, the thing you will actually interact with! If all
goes according to plan, you should see our robot in its own little world!
## Installing developer tools
-After you have verified that your Git setup is working appopriately, take a look
+After you have verified that your Git setup is working appropriately, take a look
at installing some developer tools on the [Developer Tools](/software/devtools)
page.
diff --git a/docs/software/help.md b/docs/software/help.md
index 060f8376b..f8250fa70 100644
--- a/docs/software/help.md
+++ b/docs/software/help.md
@@ -63,7 +63,7 @@ for examples of it being used.
## Search the internet
If your problem is not MIL-specific (issue with Linux, ROS, C++, etc),
-somone has most likely had the same problem and written about it on the internet.
+someone has most likely had the same problem and written about it on the internet.
You'll be surprised how often you can fix your issue by Googling the error.
## Search Slack
diff --git a/docs/software/noetic_migration.md b/docs/software/noetic_migration.md
index 6a79ec10a..6a93a86cd 100644
--- a/docs/software/noetic_migration.md
+++ b/docs/software/noetic_migration.md
@@ -45,7 +45,7 @@ before you commit.
Great, the code is now pretty! :D
-If you ran `python-modernize`, it will have suggested some changes to you, indcated
+If you ran `python-modernize`, it will have suggested some changes to you, indicated
by `+` and `-` signs. It may look something like this:
```diff
diff --git a/docs/subjugator/index.rst b/docs/subjugator/index.rst
index 28566c2ac..7a9416713 100644
--- a/docs/subjugator/index.rst
+++ b/docs/subjugator/index.rst
@@ -16,6 +16,8 @@ SubjuGator 8
Enabling
Cameras
PID Controller
+ Nav Tube
+ Watercooling
electrical
diff --git a/docs/subjugator/nav_tube.rst b/docs/subjugator/nav_tube.rst
new file mode 100644
index 000000000..0456994ec
--- /dev/null
+++ b/docs/subjugator/nav_tube.rst
@@ -0,0 +1,98 @@
+========
+Nav Tube
+========
+
+One of the major components of SubjuGator 8 is the navigation (nav tube). This pressure vessel is located right below the main pressure vessel and contains all of our navigation sensors and equipment. The navigation computer located inside the vessel allows access to the data from these components through a direct ethernet connection.
+
+.. warning::
+
+ This system was originally used on SubjuGator 7 and it was ported over with little to no changes in hardware. This does mean that the system will need a major overhaul for continued use of SubjuGator 8.
+
+Navigation Computer
+===================
+
+The navigation computer consists of a Gumstix Overo Computer-on-Module that mounts to a carrier board. The carrier board contains headers for the Teledyne Dopper Velocity Logger (DVL) connector board, Analog Devices Inertial Measurement Unit (IMU), and the pressure sensor. At one point, the navigation computer was also connected to a GPS antenna.
+
+.. warning::
+
+ No documentation or PCB design files exist for the navigation computer carrier board and there are no more functioning spare boards. Additionally, only the newer GumStix Overo COM boards are available to purchase (with a lead time of roughly 1 year) which may not be compatible with the current system. Be very careful when working inside of the navigation tube.
+
+Troubleshooting The Nav Tube Connection
+---------------------------------------
+
+If you cannot ping the Navigation Computer (192.168.37.61), please ensure (in the following order) that:
+
+* You are pinging 192.168.37.61.
+* The ethernet subconn cable has been connected between both pressure vessels.
+* You restart the sub at least once.
+* That the proper ethernet interface is configured in /etc/netplan YAML file. You may need to check ifconfig for the 'enpXs0' interface (where X is a whole number) if you have unplugged and replugged anything in the sub recently (especially the graphics card). Make sure to test the netplan with ``sudo netplan try`` so that you don't get locked out of the sub because of a bad configuration!
+* The ethernet cables are properly connected inside the main pressure vessel.
+* The ethernet cables and other cables are properly connected inside the Nav tube.
+* The navigation computer is receiving power AND is turned on (green AND blue light on the GumStix). Make sure to be extra careful and vigilent when opening and handling the navigation computer.
+
+ADIS16400/16405-BMLZ IMU & Magnetometer
+===========================================
+
+The `ADIS16400-BMLZ `_ / `ADIS16405-BMLZ `_ is the device responsible for tracking our position and orientation in the water. Currently, there is an ADIS16400 IMU in the sub, but it previously used an ADIS16405.
+
+.. warning::
+
+ These components are obsolete! It may be difficult to find replacement parts in the future if SubjuGator 8 will see continued use...
+
+Calibrating the Magnetometer
+----------------------------
+
+The magnetometer inside of the ADIS16400/16405 measures the strength of the magnetic field at the orientation it faces. We use this data in conjunction with the IMU's gyroscopes and accelerometers to determine the orientation of the sub in the water. The process of calibrating the magnetometer is called magnetic hardsoft compensation and essentially changes how we bias the data it gives us.
+
+.. note::
+
+ Calibrating the magnetometer must be done in a pool.
+
+To calibrate the magnetometer you must first collect magnetometer data (``/imu/mag_raw``) to use for the calibration script. This can be done through the following:
+
+.. code-block:: bash
+
+ $ roslaunch subjugator_launch sub8.launch
+
+or if you prefer to not launch the entire sub:
+
+.. code-block:: bash
+
+ $ roslaunch subjugator_launch nav_box.launch imu:=true
+
+Then, in a separate terminal window, navigate to a known directory start recording the rosbag by typing:
+
+.. code-block:: bash
+
+ $ rosbag record -O .bag /imu/mag_raw
+
+where is a substitute for whatever name you want to give to your bag (I recommend something memorable, like Frank or Penelope). This will record the bag data in the directory that the terminal window is in.
+
+When you have started recording the bag, have members who are in the water rotate the sub. Only the sub should move, not the members holding onto the sub. The calibration can be done in any order, but you must complete a full roll, pitch, and yaw rotation plus have a few minutes of data with all three occurring at the same time. Once you are done collecting data, kill the recording window using ``ctrl+c``.
+
+Next, we must run the calibration script with our data. This script is located in ``SubjuGator/drivers/magnetic_compensation/sub8_magnetic_hardsoft_compensation/scripts``. Type the following:
+
+.. code-block:: bash
+
+ $ ./generate_config
+
+note that this is a python script, so
+
+.. code-block:: bash
+
+ $ python3 generate_config
+
+is also valid.
+
+.. note::
+
+ If the script fails because of the ``fit_ellipsoid`` method and the points on the first figure are colinear or nearly colinear you may not have collected thorough enough data. The alternate possibility is a malfunctioning magnetometer.
+
+The output of the script should be a 3x3 matrix labeled ``scale`` and a length 3 vector labeled ``shift``. These values go into the ``scale`` and ``shift`` values located inside of ``subjugator_launch/launch/subsystems/nav_box.launch``.
+
+After running ``cm``, you will have (hopefully) successfully calibrated the magnetometer. Make sure to test the sub after calibration to see if the new configuration values are an improvement over the old ones.
+
+Important Links and Datasheets
+==============================
+
+- `ADIS16400/ADIS16405 Datasheet `_
diff --git a/docs/subjugator/watercooling.rst b/docs/subjugator/watercooling.rst
new file mode 100644
index 000000000..5344e68bf
--- /dev/null
+++ b/docs/subjugator/watercooling.rst
@@ -0,0 +1,70 @@
+============
+Watercooling
+============
+
+SubjuGator 8's hardware requires a watercooling loop for the CPU, graphics card, and ESCs.
+
+Filling the Water cooling Loop
+==============================
+
+.. note::
+
+ Filling the water cooling loop requires at least 2 people.
+
+Materials
+---------
+
+* Sub Shore Power Supply
+* Sub battery tube cover
+* Sub battery cables
+* Large Funnel
+* Small Funnel
+* Stool or Chair
+* Deionized Water w/ Biocide
+* Vacuum Pump
+* Extra water cooling connectors and tubing
+* Water cooling reservoir
+* Bucket
+
+.. note::
+
+ While deionized water with biocide is preferred for longevity, distilled water will work fine. You should not use purified water. Bonus points if the water is dyed orange :)
+
+No-Pump Procedure
+-----------------
+
+These steps should be taken when there is no external pump to help with the filling process.
+
+.. warning::
+
+ Exercise caution during steps 8 and 9 as the sub will be powered on with a water hazard nearby.
+
+#. Move the main vessel onto the wooden platform and down to the floor.
+#. Set up the environment as shown in the picture below.
+#. Gravity feed the system by filling the reservoir with water and letting the bubbles come out naturally. Move on when no more bubbles come out.
+#. Empty the reservoir until the water is below the "stove pipe" (metal tube inside the reservoir).
+#. Blow into the tube exposed to air to force the water into the loop while extracting the air inside of the loop. Make sure to fill the reservoir until the water is below the "stove pipe" when there is an air gap inside of the water inlet tube. Move on when you cannot remove any more bubbles.
+#. Attach the vacuum pump to the tube exposed to air and pump until the pressure reaches around 10 PSI. Pinch the outlet tube and break the vacuum to allow water to fill the low pressure spots. Repeat this step until at least a decent amount of water makes it past the pump.
+#. With water at the ready, connect the sub to shore power and fill the reservoir with water (you do not have to worry about the "stove pipe").
+#. Wiggle the sub around while the pump is running to extract any trapped bubbles.
+
+Emptying the Water Cooling Loop
+===============================
+
+The water cooling loop should be emptied before the sub is shipped anywhere. Emptying the water cooling loop is easier than filling it up.
+
+.. note::
+
+ Emptying the water cooling loop requires at least 2 people.
+
+Materials
+---------
+
+* Vacuum pump
+* Extra water cooling connectors and tubing
+* Water cooling reservoir
+* Bucket
+
+
+Procedure
+---------
diff --git a/docs/testingprocedures.md b/docs/testingprocedures.md
index 2fcf81852..b1a6d4dc5 100644
--- a/docs/testingprocedures.md
+++ b/docs/testingprocedures.md
@@ -2,6 +2,8 @@
## Before leaving
+For best results, packing should be done at least one day before a testing session. This
+
### Packing list
* Power Strip
* Table
@@ -16,7 +18,6 @@
* 5/32 Allen Key
* Duct tape and scissor
* Buoyancy foams for the sub
-* Allen Key for paintball tank
* Pliers
* Flat-head screwdriver
* Kill wand
@@ -27,22 +28,22 @@
* O'ring grease (Molykote 55)
* Cable grease (Molykote 44)
* Hot glue gun
-* Zip ties
+* Hot glue sticks
+* Large and small zip ties
* clippers
-* Towels
+* Towel(s)
* [Sunscreen](https://www.youtube.com/watch?v=sTJ7AzBIJoI)
-
+* Tent (If going to Graham Pool or Florida Pool)
+* Chairs (If going to Graham Pool)
### Software/Electrical Checklist
-* Update and build code
-* Verify all sensors output data
-* Verify thrusters spin given command
-* Verify kill (soft an hard)
-* Grease all electrical connectors appropriately
-
+* Update (`git pull`) and build (`cm`) code.
+* Verify all sensors output data.
+* Verify that the correct thrusters spin given the appropriate command.
+* Verify kill (soft and hard).
+* Grease all electrical connectors appropriately.
## At testing site
-
* Get wall power to powerstrip.
* Setup and connect to Network Box.
* Roll tether and connect it to network box. **(DO NOT USE POE)**
@@ -51,11 +52,11 @@
* SSH into sub.
* Start tmux, write code.
* Grease O-rings with Molykote 55 every time a pressure vessel is closed.
-* Make sure ALL pneumatic tubes are inserted correctly. **(DO NOT FLOOD THE VALVE BOX)**
-* Make sure all holes to paintball tank are sealed correctly. **(THIS WILL ALSO RESULT IN FLOODING IF NOT DONE)**
+* * **ENSURE THAT THE RED PRESSURE RELIEF CAP ON THE BATTERY TUBE HAS BEEN SCREWED IN PLACE AFTER CHANGING BATTERIES**
* Person getting into the pool must do backflip.
-* Deploy sub. (check for bubbles, make sure buoyancy is correct)
+* Deploy sub. (check for bubbles, make sure buoyancy is correct).
* Verify odometry.
-What happens when the valve box isn't closed:
-![What happens when the valve box isn't closed.](/flooded_valve_box.jpg)
+### Troubleshooting
+
+- :ref:`Troubleshooting The Nav Tube Connection`
diff --git a/mil_common/axros b/mil_common/axros
index 1b0399935..a4951d333 160000
--- a/mil_common/axros
+++ b/mil_common/axros
@@ -1 +1 @@
-Subproject commit 1b03999351fb5a61b202ff125f493229c2a1676b
+Subproject commit a4951d33356c349856532ddef5c97c6ec6810c28
diff --git a/mil_common/drivers/mil_passive_sonar/README.md b/mil_common/drivers/mil_passive_sonar/README.md
index 572ad4069..7010a3ae0 100644
--- a/mil_common/drivers/mil_passive_sonar/README.md
+++ b/mil_common/drivers/mil_passive_sonar/README.md
@@ -4,7 +4,7 @@ This package includes the main algorithm to find the direction of a pinger. It a
# Running:
Ensure that hydrophones -> ros is running and publishing a `mil_passive_sonar/Ping` msg.
-Then run `roslaunch mil_passive_sonar mil_passive_sonar.lauch`
+Then run `roslaunch mil_passive_sonar mil_passive_sonar.launch`
`mil_passive_sonar/FindPinger`
diff --git a/mil_common/drivers/mil_passive_sonar/scripts/triggering.py b/mil_common/drivers/mil_passive_sonar/scripts/triggering.py
index 897a76949..321a20411 100755
--- a/mil_common/drivers/mil_passive_sonar/scripts/triggering.py
+++ b/mil_common/drivers/mil_passive_sonar/scripts/triggering.py
@@ -96,7 +96,7 @@ def get_params(self):
self.enabled = rospy.get_param("~enable_on_launch")
# Attributes about our target frequency range
- # target Frquency in Hz
+ # target Frequency in Hz
self.target = rospy.get_param("~target_frequency")
# tolerance around that frequerncy in Hz
tolerance = rospy.get_param("~frequency_tolerance")
@@ -121,7 +121,7 @@ def get_params(self):
self.v_sound = rospy.get_param("v_sound")
# Misc attributes
- # minimum gradient of the max convolution wrt time to trigger a time of arivals calculation
+ # minimum gradient of the max convolution wrt time to trigger a time of arrivals calculation
self.threshold = rospy.get_param("~threshold")
self.trigger_offset = rospy.get_param("~trigger_offset")
# how far after the triggering time to make upper bound of samples at triggering in sec
diff --git a/mil_common/drivers/mil_pneumatic_actuator/nodes/pneumatic_actuator_node b/mil_common/drivers/mil_pneumatic_actuator/nodes/pneumatic_actuator_node
index bf8261177..920fb5a92 100755
--- a/mil_common/drivers/mil_pneumatic_actuator/nodes/pneumatic_actuator_node
+++ b/mil_common/drivers/mil_pneumatic_actuator/nodes/pneumatic_actuator_node
@@ -37,7 +37,7 @@ class Actuator:
if isinstance(config, int):
return cls.from_int(config)
type_str = config["type"]
- pulse_time = config["pulse_time"] if "pulse_time" in config else None
+ pulse_time = config.get("pulse_time")
open_id = config["ports"]["open_port"]["id"]
open_default = config["ports"]["open_port"]["default"]
if "close_port" in config["ports"]:
diff --git a/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub8/utils.py b/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub8/utils.py
index 0ef0cf9a1..7524e6dfe 100644
--- a/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub8/utils.py
+++ b/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub8/utils.py
@@ -114,13 +114,11 @@ def __bytes__(self) -> bytes:
@overload
@classmethod
- def _unpack_payload(cls, data: Literal[b""]) -> None:
- ...
+ def _unpack_payload(cls, data: Literal[b""]) -> None: ...
@overload
@classmethod
- def _unpack_payload(cls, data: bytes) -> bytes:
- ...
+ def _unpack_payload(cls, data: bytes) -> bytes: ...
@classmethod
def _unpack_payload(cls, data: bytes) -> bytes | None:
@@ -455,13 +453,11 @@ def calculate_checksum(self, data: bytes) -> int:
@overload
@classmethod
- def from_bytes(cls, data: Literal[b""]) -> None:
- ...
+ def from_bytes(cls, data: Literal[b""]) -> None: ...
@overload
@classmethod
- def from_bytes(cls: type[T], data: bytes) -> T:
- ...
+ def from_bytes(cls: type[T], data: bytes) -> T: ...
@classmethod
def from_bytes(cls: type[T], data: bytes) -> T | None:
diff --git a/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub9/sub9_driver.py b/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub9/sub9_driver.py
index 59db73c99..90928ff8d 100755
--- a/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub9/sub9_driver.py
+++ b/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub9/sub9_driver.py
@@ -31,8 +31,9 @@ class SimulatedUSBtoCANStream(SimulatedSerial):
def __init__(
self,
- devices: list[tuple[type[SimulatedCANDeviceHandle], list[type[Packet]]]]
- | None = None,
+ devices: (
+ list[tuple[type[SimulatedCANDeviceHandle], list[type[Packet]]]] | None
+ ) = None,
):
"""
Args:
@@ -214,16 +215,14 @@ def read_devices(
self,
*,
simulated: Literal[True],
- ) -> list[tuple[type[SimulatedCANDeviceHandle], list[type[Packet]]]]:
- ...
+ ) -> list[tuple[type[SimulatedCANDeviceHandle], list[type[Packet]]]]: ...
@overload
def read_devices(
self,
*,
simulated: Literal[False],
- ) -> list[tuple[type[CANDeviceHandle], list[type[Packet]]]]:
- ...
+ ) -> list[tuple[type[CANDeviceHandle], list[type[Packet]]]]: ...
def read_devices(
self,
diff --git a/mil_common/drivers/mil_usb_to_can/test/test_packets_sub9.py b/mil_common/drivers/mil_usb_to_can/test/test_packets_sub9.py
index 01c1dc47a..c58a8c32c 100755
--- a/mil_common/drivers/mil_usb_to_can/test/test_packets_sub9.py
+++ b/mil_common/drivers/mil_usb_to_can/test/test_packets_sub9.py
@@ -8,7 +8,7 @@
@dataclass
-class TestPacket(Packet, msg_id=0x47, subclass_id=0x44, payload_format="BHf"):
+class TestPacket(Packet, msg_id=0x47, subclass_id=0x44, payload_format="?Hd"):
example_bool: bool
example_int: int
example_float: float
@@ -23,7 +23,7 @@ def test_simple_packet(self):
packet = TestPacket(False, 42, 3.14)
self.assertEqual(packet.msg_id, 0x47)
self.assertEqual(packet.subclass_id, 0x44)
- self.assertEqual(packet.payload_format, "BHf")
+ self.assertEqual(packet.payload_format, "?Hd")
self.assertEqual(packet.example_bool, False)
self.assertEqual(packet.example_int, 42)
self.assertEqual(packet.example_float, 3.14)
@@ -36,6 +36,13 @@ def test_assembled_packet(self):
self.assertEqual(assembled[2], packet.msg_id)
self.assertEqual(assembled[3], packet.subclass_id)
+ def test_format(self):
+ packet = TestPacket(False, 42, 3.14)
+ self.assertEqual(
+ TestPacket.from_bytes(TestPacket.__bytes__(packet)),
+ packet,
+ )
+
def test_comparisons(self):
packet = TestPacket(False, 42, 3.14)
packet_two = TestPacket(False, 42, 3.14)
diff --git a/mil_common/gnc/odometry_utils/src/odometry_to_tf.cpp b/mil_common/gnc/odometry_utils/src/odometry_to_tf.cpp
index d2ec5a6bf..953f0fcbd 100644
--- a/mil_common/gnc/odometry_utils/src/odometry_to_tf.cpp
+++ b/mil_common/gnc/odometry_utils/src/odometry_to_tf.cpp
@@ -4,7 +4,9 @@
#include
#include
+#include