Skip to content

Conversation

@emilyzucker1
Copy link
Contributor

Monitoring node outputs to terminal when a spike has been detected. Only extremely large spikes will be detected, such as crashing into a wall. Below are some screenshots showing spikes.

Before spiking: Screenshot from 2025-11-02 19-23-58

After crashing into wall:
Screenshot from 2025-11-02 19-24-38

After crashing into floor:
Screenshot from 2025-11-02 19-25-08

@emilyzucker1 emilyzucker1 linked an issue Nov 3, 2025 that may be closed by this pull request
@Carlosdc25
Copy link
Contributor

This looks really good and I can confirm that it works when I switch to your branch!!!

Now for my critiques

  • The created topics are just republishing sensor data. I don't really see the point in having them. We could still have designated topics for imu and dvl but maybe instead of republishing sensor data we can publish whether or not a spike is detected. You can probably publish a message thats composed of a boolean and string explaining what the cause of the spike is.

  • No DVL is being used.

  • We want this node to not be in the localization launch file so that way we can launch it separately.

On a different note, I pulled main into this branch and will push it now. So you can now make relative movments using commands

move_rel <x> <y> <z> <rx> <ry> <rz>

This will make the submarine move relative to its current position. If you choose to omit some of the values like

move_rel 0 1

Then the rest of the values will be assumed to be zero.

I think it would be good to use this command to test your monitor. I used it to test hitting the ground and IT WORKED!

Overall good job

Copy link
Contributor

@Carlosdc25 Carlosdc25 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Followed the comments I made previously

Copy link
Member

@mohana-pamidi mohana-pamidi left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Great Job Emily!

Tomorrow we will be testing the monitoring a little more, including seeing if it detects a spike when the sub is moving at a constant velocity and stops suddenly.

As mentioned by Carlos, we will be moving the monitoring script to it's own package (not in localization), and instead of republishing the sensor data, we will be publishing spike detection messages.

Comment on lines 13 to 17
self.pub_dvl_ = self.create_publisher(Odometry, "monitoring_dvl", 10)
self.pub_imu_ = self.create_publisher(Imu, "monitoring_imu", 10)

self.create_subscription(Odometry, "dvl/odom", self.dvl_odom_callback, 10)
self.create_subscription(Imu, "imu/data", self.imu_data_callback, 10)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No need to publish the same message type. I would suggest publishing your own message type that has monitoring metrics of interest

Comment on lines 27 to 28
def dvl_odom_callback(self, dmsg: Odometry):
self.pub_dvl_.publish(dmsg)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why are we republishing?

Comment on lines 31 to 32
# create running average for relevant measurements:
# acceleration x
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Use docstrings:

Suggested change
# create running average for relevant measurements:
# acceleration x
"""
create running average for relevant measurements:
acceleration x
"""

Comment on lines 33 to 61
if len(self.imu_accelerationx_array) <= 20:
self.imu_accelerationx_array.append(imsg.linear_acceleration.x)
else:
imu_accelerationx_avg = (
abs(self.imu_accelerationx_array[0])
+ abs(self.imu_accelerationx_array[1])
+ abs(self.imu_accelerationx_array[2])
+ abs(self.imu_accelerationx_array[3])
+ abs(self.imu_accelerationx_array[4])
+ abs(self.imu_accelerationx_array[5])
+ abs(self.imu_accelerationx_array[6])
+ abs(self.imu_accelerationx_array[7])
+ abs(self.imu_accelerationx_array[8])
+ abs(self.imu_accelerationx_array[9])
+ abs(self.imu_accelerationx_array[10])
+ abs(self.imu_accelerationx_array[11])
+ abs(self.imu_accelerationx_array[12])
+ abs(self.imu_accelerationx_array[13])
+ abs(self.imu_accelerationx_array[14])
+ abs(self.imu_accelerationx_array[15])
+ abs(self.imu_accelerationx_array[16])
+ abs(self.imu_accelerationx_array[17])
+ abs(self.imu_accelerationx_array[18])
+ abs(self.imu_accelerationx_array[19])
) / len(self.imu_accelerationx_array)
percent_diff = (
(abs(imsg.linear_acceleration.x) - imu_accelerationx_avg)
/ imu_accelerationx_avg
) * 100
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Write DRY code!

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The IMU callback function is way too redundant, consider writing private methods to abstract the logic.

@emilyzucker1
Copy link
Contributor Author

added private function, removed the statements to republish data.

@emilyzucker1
Copy link
Contributor Author

dvl spike functionality has been added, as well as using a unique message to output spike information.
Screenshot from 2025-12-09 13-02-01

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

Test Spike Monitoring Node

6 participants