diff --git a/SubjuGator/command/subjugator_launch/config/adaptive_controller.yaml b/SubjuGator/command/subjugator_launch/config/adaptive_controller.yaml
index c6406c44d..aefd3cb36 100644
--- a/SubjuGator/command/subjugator_launch/config/adaptive_controller.yaml
+++ b/SubjuGator/command/subjugator_launch/config/adaptive_controller.yaml
@@ -1,6 +1,6 @@
---
-kp: 1000, 1000, 1000, 5000, 5000, 5000
-kd: 150, 150, 150, 50, 100, 25
-kg: 5,5,5,5,5,5
-ki: 5,5,5,5,10,5
-use_learned: false
+kp: 120, 150, 200, 100, 50, 50
+kd: 25, 25, 25, 25, 25, 25
+kg: 2.5,2.5,2.5,2.5,2.5,2.5
+ki: 2.5,2.5,2.5,2.5,2.5,2.5
+use_learned: true
diff --git a/SubjuGator/command/subjugator_launch/config/adaptive_controller_gazebo.yaml b/SubjuGator/command/subjugator_launch/config/adaptive_controller_gazebo.yaml
new file mode 100644
index 000000000..c6406c44d
--- /dev/null
+++ b/SubjuGator/command/subjugator_launch/config/adaptive_controller_gazebo.yaml
@@ -0,0 +1,6 @@
+---
+kp: 1000, 1000, 1000, 5000, 5000, 5000
+kd: 150, 150, 150, 50, 100, 25
+kg: 5,5,5,5,5,5
+ki: 5,5,5,5,10,5
+use_learned: false
diff --git a/SubjuGator/command/subjugator_launch/launch/bag_debugging_controller.launch b/SubjuGator/command/subjugator_launch/launch/bag_debugging_controller.launch
new file mode 100644
index 000000000..4c6024669
--- /dev/null
+++ b/SubjuGator/command/subjugator_launch/launch/bag_debugging_controller.launch
@@ -0,0 +1,7 @@
+
+
+
+
+
+
+
diff --git a/SubjuGator/command/subjugator_launch/launch/can.launch b/SubjuGator/command/subjugator_launch/launch/can.launch
index 813b94625..b46fbd8ba 100644
--- a/SubjuGator/command/subjugator_launch/launch/can.launch
+++ b/SubjuGator/command/subjugator_launch/launch/can.launch
@@ -5,7 +5,7 @@
# Path of serial device
- port: /dev/serial/by-id/usb-FTDI_FT232R_USB_UART_A800GHCF-if00-port0
+ port: /dev/serial/by-id/usb-FTDI_FT232R_USB_UART_A50285BI-if00-port0
# Baudrate of device, should leave as is
baudrate: 115200
# List of python device handle classes
diff --git a/SubjuGator/command/subjugator_launch/launch/sub8.launch b/SubjuGator/command/subjugator_launch/launch/sub8.launch
index 178efc6bb..247fe1e62 100644
--- a/SubjuGator/command/subjugator_launch/launch/sub8.launch
+++ b/SubjuGator/command/subjugator_launch/launch/sub8.launch
@@ -39,7 +39,9 @@
-
+
+
+
diff --git a/SubjuGator/command/subjugator_launch/launch/subsystems/adaptive_controller.launch b/SubjuGator/command/subjugator_launch/launch/subsystems/adaptive_controller.launch
index 17bd1d3ac..a758c4278 100644
--- a/SubjuGator/command/subjugator_launch/launch/subsystems/adaptive_controller.launch
+++ b/SubjuGator/command/subjugator_launch/launch/subsystems/adaptive_controller.launch
@@ -1,8 +1,10 @@
-
+
+
-
-
+
+
+
diff --git a/SubjuGator/command/subjugator_launch/package.xml b/SubjuGator/command/subjugator_launch/package.xml
index 6a6beeeb6..e3f6ef4ba 100644
--- a/SubjuGator/command/subjugator_launch/package.xml
+++ b/SubjuGator/command/subjugator_launch/package.xml
@@ -5,8 +5,10 @@
The subjugator_launch package
Jacob Panikulam
MIT
+ rosbag
roslaunch
roslaunch
+ rosbag
robot_state_publisher
nodelet
c3_trajectory_generator
diff --git a/SubjuGator/command/subjugator_launch/scripts/depth_conn b/SubjuGator/command/subjugator_launch/scripts/depth_conn
index 13bf8a480..c63922eb9 100755
--- a/SubjuGator/command/subjugator_launch/scripts/depth_conn
+++ b/SubjuGator/command/subjugator_launch/scripts/depth_conn
@@ -1,2 +1,2 @@
#!/bin/sh
-exec socat -d -d pty,link=/tmp/depth,raw,echo=0 tcp:mil-sub-gumstix.ad.mil.ufl.edu:33056
+exec socat -d -d pty,link=/tmp/depth,raw,echo=0 tcp:192.168.37.61:33056
diff --git a/SubjuGator/command/subjugator_launch/scripts/dvl_conn b/SubjuGator/command/subjugator_launch/scripts/dvl_conn
index f0be15464..745a45097 100755
--- a/SubjuGator/command/subjugator_launch/scripts/dvl_conn
+++ b/SubjuGator/command/subjugator_launch/scripts/dvl_conn
@@ -1,2 +1,2 @@
#!/bin/sh
-exec socat -d -d pty,link=/tmp/dvl,raw,echo=0 tcp:mil-sub-gumstix.ad.mil.ufl.edu:349
+exec socat -d -d pty,link=/tmp/dvl,raw,echo=0 tcp:192.168.37.61:349
diff --git a/SubjuGator/command/subjugator_launch/scripts/imu_conn b/SubjuGator/command/subjugator_launch/scripts/imu_conn
index 59275c393..bc93e1eb1 100755
--- a/SubjuGator/command/subjugator_launch/scripts/imu_conn
+++ b/SubjuGator/command/subjugator_launch/scripts/imu_conn
@@ -1,2 +1,2 @@
#!/bin/sh
-exec socat -d -d pipe:/tmp/imu,wronly=1 tcp:mil-sub-gumstix.ad.mil.ufl.edu:1382
+exec socat -d -d pipe:/tmp/imu,wronly=1 tcp:192.168.37.61:1382
diff --git a/SubjuGator/gnc/subjugator_thruster_mapper/config/thruster_layout.yaml b/SubjuGator/gnc/subjugator_thruster_mapper/config/thruster_layout.yaml
index 2d3de8ac9..48992559a 100644
--- a/SubjuGator/gnc/subjugator_thruster_mapper/config/thruster_layout.yaml
+++ b/SubjuGator/gnc/subjugator_thruster_mapper/config/thruster_layout.yaml
@@ -30,7 +30,7 @@ thruster_ports:
# mapping from thrust in Newtons to effort (e = t[0]x^4 + t[1]x^3 + t[2]x^2 + t[3]x)
thrusters:
FLH: {
- node_id: 3,
+ node_id: 4,
position: [0.2678, 0.2795, 0.0],
direction: [0.866, -0.5, 0.0],
thrust_bounds: [-81.85, 99.7],
@@ -42,7 +42,7 @@ thrusters:
}
}
FLV: {
- node_id: 1,
+ node_id: 5,
position: [0.1583, 0.169, 0.0142],
direction: [0.0, 0.0, 1.0],
thrust_bounds: [-81.85, 99.7],
@@ -54,7 +54,7 @@ thrusters:
}
}
FRH: {
- node_id: 2,
+ node_id: 0,
position: [0.2678, -0.2795, 0.0],
direction: [0.866, 0.5, 0.0],
thrust_bounds: [-81.85, 99.7],
@@ -66,9 +66,9 @@ thrusters:
}
}
FRV: {
- node_id: 0,
+ node_id: 1,
position: [0.1583, -0.169, 0.0142],
- direction: [0.0, 0.0, -1.0],
+ direction: [0.0, 0.0, 1.0],
thrust_bounds: [-81.85, 99.7],
calib: {
# yamllint disable-line rule:line-length
@@ -78,7 +78,7 @@ thrusters:
}
}
BLH: {
- node_id: 4,
+ node_id: 3,
position: [-0.2678, 0.2795, 0.0],
direction: [0.866, 0.5, 0.0],
thrust_bounds: [-81.85, 99.7],
@@ -90,7 +90,7 @@ thrusters:
}
}
BLV: {
- node_id: 5,
+ node_id: 6,
position: [-0.1583, 0.169, 0.0142],
direction: [0.0, 0.0, 1.0],
thrust_bounds: [-81.85, 99.7],
@@ -102,7 +102,7 @@ thrusters:
}
}
BRH: {
- node_id: 6,
+ node_id: 7,
position: [-0.2678, -0.2795, 0.0],
direction: [0.866, -0.5, 0.0],
thrust_bounds: [-81.85, 99.7],
@@ -114,7 +114,7 @@ thrusters:
}
}
BRV: {
- node_id: 7,
+ node_id: 2,
position: [-0.1583, -0.169, 0.0142],
direction: [0.0, 0.0, 1.0],
thrust_bounds: [-81.85, 99.7],
diff --git a/SubjuGator/simulation/subjugator_gazebo/urdf/sub8.urdf.xacro b/SubjuGator/simulation/subjugator_gazebo/urdf/sub8.urdf.xacro
index 3f4517335..9290884dd 100644
--- a/SubjuGator/simulation/subjugator_gazebo/urdf/sub8.urdf.xacro
+++ b/SubjuGator/simulation/subjugator_gazebo/urdf/sub8.urdf.xacro
@@ -11,6 +11,8 @@
+
+
@@ -31,6 +33,11 @@
+
+
+
+
+
diff --git a/docs/subjugator/index.rst b/docs/subjugator/index.rst
index c34f4e7fd..28566c2ac 100644
--- a/docs/subjugator/index.rst
+++ b/docs/subjugator/index.rst
@@ -15,6 +15,7 @@ SubjuGator 8
Simulating
Enabling
Cameras
+ PID Controller
electrical
diff --git a/docs/subjugator/pid.rst b/docs/subjugator/pid.rst
new file mode 100644
index 000000000..c2feeae29
--- /dev/null
+++ b/docs/subjugator/pid.rst
@@ -0,0 +1,26 @@
+PID Controller
+--------------
+
+SubjuGator 8 uses 6 PID controllers for its 6 degrees of freedom (x, y, z, roll, pitch, yaw). The gain for these PID controllers can be adjusted in ``adaptive_controller.yaml`` found in the ``subjugator_launch/config`` directory. Since the weight of the sub shifts with each component modified, the PID controller values have to be adjusted from time to time. There are two approaches to adjust PID values in the water:
+
+1. Have someone with experience in tuning PID controllers swim with the sub and use the sub's response to movement commands to adjust the gains.
+2. Eliminate the error in each axis by adjusting the gains and evaluating the RMS error in each axis after sending the same movement commands.
+
+PID Controller Tuning Tips
+~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+* The learning gains (``ki`` and ``kd``) provide very little input to the wrenches applied to the sub, so it is better to treat it as a PD controller to start with. You can disable the learning gains using ``use_learned: false``.
+* While you are tuning the PID values, keep a history of the values you have tried for further analysis during and after testing. You can use ``scp`` for this, but it may just be easier to take a screenshot or a photo. You can also take videos of the sub from the side of the pool to reference later.
+
+PID Debugging Data Collection
+~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+.. code-block:: bash
+
+ $ roslaunch subjugator_launch bag_debugging_controller.launch prefix_name:="my_prefix"
+
+This launch file records a bag file containing adaptive controller ``pose_error``, ``twist_error``, ``adaptation``, ``dist``, and ``drag`` data along with ``wrench``, ``trajectory``, ``odom``, ``imu/data_raw``, and ``dvl/range`` data. This data is useful in determining if the PID values are getting better or worse using simulations. The resulting bag file will be located in ``gnc/subjugator_controller/debug_bags/``. This launch file was written by Andres Pulido.
+
+.. warning::
+
+ This launch file needs the sub launch file (``sub8.launch``) running in order to function properly.