Skip to content

Commit

Permalink
Merge branch 'master' into AddDocCodeStruct_998
Browse files Browse the repository at this point in the history
  • Loading branch information
cbrxyz authored Oct 19, 2023
2 parents 09556d6 + 0a606c4 commit 04e1a01
Show file tree
Hide file tree
Showing 16 changed files with 293 additions and 128 deletions.
20 changes: 0 additions & 20 deletions .github/ISSUE_TEMPLATE/navigator.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
6 changes: 3 additions & 3 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ repos:
hooks:
- id: yamllint
- repo: https://github.com/psf/black
rev: 23.7.0
rev: 23.9.1
hooks:
- id: black
- repo: https://github.com/pre-commit/mirrors-clang-format
Expand All @@ -28,7 +28,7 @@ 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
Expand All @@ -40,7 +40,7 @@ repos:
exclude: ^docker|deprecated|NaviGator/simulation/VRX
- repo: https://github.com/astral-sh/ruff-pre-commit
# Ruff version.
rev: 'v0.0.287'
rev: 'v0.0.292'
hooks:
- id: ruff
args: [--fix, --exit-non-zero-on-fix]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
<param name="/is_vrx" type="bool" value="True" />

<include file="$(find navigator_launch)/launch/gnc/thruster_mapper.launch"/>
<include file="$(find navigator_launch)/launch/vrx/vrx_classifier.launch" />
<include file="$(find navigator_launch)/launch/vrx/vrx_tf.launch" />
<include file="$(find navigator_launch)/launch/vrx/vrx_localization.launch" />
<include file="$(find navigator_launch)/launch/vrx/vrx_upload_urdf.launch" />
Expand All @@ -30,5 +31,4 @@

<node if="$(arg run_task)" name="run_vrx_task" pkg="mil_missions" type="mission_client"
args="run Vrx" output="screen" />
<include file="$(find navigator_launch)/launch/vrx/vrx_classifier.launch" />
</launch>
144 changes: 71 additions & 73 deletions NaviGator/mission_control/navigator_missions/vrx_missions/vrx.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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")
Expand All @@ -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

Expand All @@ -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

Expand Down Expand Up @@ -150,7 +151,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)
Expand All @@ -168,7 +169,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")
Expand All @@ -183,8 +184,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(),
},
),
)
9 changes: 9 additions & 0 deletions SubjuGator/etc/motd
Original file line number Diff line number Diff line change
@@ -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!
7 changes: 0 additions & 7 deletions SubjuGator/simulation/subjugator_gazebo/urdf/sub8.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,6 @@
<xacro:include filename="$(find mil_gazebo)/xacro/passive_sonar.xacro"/>
<xacro:include filename="$(find mil_gazebo)/xacro/inclinometer.xacro"/>

<link name="world"/>

<!-- Base link of sub -->
<link name="base_link">
<inertial>
Expand All @@ -33,11 +31,6 @@
</collision>
</link>

<joint name="dummy_joint" type="fixed">
<parent link="world"/>
<child link="base_link"/>
</joint>

<!-- Sensors -->
<xacro:mil_fixed_link name="front_stereo" parent="base_link" xyz="0.2559 0 0.1707" rpy="0 0 0"/>
<xacro:mil_camera name="front_left_cam" parent="front_stereo" namespace="/camera/front/left" xyz="0 0.0445 0" rpy="0 0 0"/>
Expand Down
2 changes: 2 additions & 0 deletions docs/subjugator/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@ SubjuGator 8
Enabling <enabling>
Cameras <cameras>
PID Controller <pid>
Nav Tube <nav_tube>
Watercooling <watercooling>

electrical

Expand Down
Loading

0 comments on commit 04e1a01

Please sign in to comment.