Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

(Last of the) Su23 documentation #1096

Merged
merged 8 commits into from
Oct 9, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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!
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
98 changes: 98 additions & 0 deletions docs/subjugator/nav_tube.rst
Original file line number Diff line number Diff line change
@@ -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 <https://www.analog.com/en/products/adis16400.html#product-overview>`_ / `ADIS16405-BMLZ <https://www.analog.com/en/products/adis16405.html#product-overview>`_ 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 <name here>.bag /imu/mag_raw

where <name here> 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 <path to calibration data bag file>

note that this is a python script, so

.. code-block:: bash

$ python3 generate_config <path to calibration data bag file>

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 <https://www.analog.com/media/en/technical-documentation/data-sheets/ADIS16400_16405.pdf>`_
70 changes: 70 additions & 0 deletions docs/subjugator/watercooling.rst
Original file line number Diff line number Diff line change
@@ -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
---------
33 changes: 17 additions & 16 deletions docs/testingprocedures.md
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand All @@ -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)**
Expand All @@ -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<troubleshooting-nav>`
Loading