Hi everyone
I’m working with BlueROV2 running ArduSub 4.1.0, equipped only with a barometer and a camera, and I’ve encountered an issue with Depth Hold mode that seems related to internal fimware logic
My ROV is occasionally disturbed and I need it to maintain its depth hold behavior as much as possible.
My test procedure is :
I bring the ROV to a desired depth manually in Manual mode.
I switch to Depth Hold mode
I apply two types of vertical disturbances by pulling the ROV upward: short disturbances (< 3 seconds) and long disturbance (> 4-9 seconds)
It seemed to me that :
For Short disturbance → The ROV returns to its original target as expected.
For Long disturbances → The ROV fails to recover its previous depth. It stabilizes near the surface between -0.2 and 0 m, and no longer attemps to return to the depth it held before the disturbance.
But after analyzing the logs, it seems that this behavior is due to the ROV detecting that it’s either at the surface or at the bottom.
(in red : CTUN.DAlt - desired altitude, in green : CTUN.Alt - altitude)
I tried writing a Python script to send a target deth to the ROV using set_position_target_global_int and I also change the SURFACE_DEPTH parameter from -10 to 0 (in centimeters) but nothing chnaged
I saw this section of code in the ModeAlthold::control_depth() function in mode_althold.cpp from ArduSub. Could this explain the behavior I’m observing ?
// desired_climb_rate returns 0 when within the deadzone.
//we allow full control to the pilot, but as soon as there's no input, we handle being at surface/bottom
if (fabsf(target_climb_rate_cm_s) < 0.05f) {
if (sub.ap.at_surface) {
position_control->set_pos_desired_U_cm(MIN(position_control->get_pos_desired_U_cm(), g.surface_depth)); // set target to 5 cm below surface level
} else if (sub.ap.at_bottom) {
position_control->set_pos_desired_U_cm(MAX(inertial_nav.get_position_z_up_cm() + 10.0f, posi-tion_control->get_pos_desired_U_cm())); // set target to 10 cm above bottom
}
Could you help me understand this behavior and whether it can be modified ?
Right now I’m considering removing this part of the code from the firmware and compiling a customized version of ArduSub
What is disturbing your vehicle, and why do you want it to ignore that?
The firmware has protections against automated futile running of the thrusters when it expects the vehicle has run into the bottom or surface, because doing that aggressively is a fast track to damaging something, either the thrusters (by sucking up sediment, or overheating in air and melting the bearings), or the vehicle or creature/object that’s being hit. That seems quite logical to me, especially if there’s no distance sensor to identify when the obstruction is gone / passed over.
The depth target is handled the same in the autopilot, regardless of whether it is set by manually piloting to the desired depth, or commanding the depth with a script.
That said, if the target is changing when you don’t want it to you could try sending it regularly so it returns to the depth you want, although I’m unsure whether the position controller has its own limits on how long it’s happy to push in a direction without making progress.
Thanks for the clarification I do understand, as it’s important to protect both the system and the environment
What is disturbing your vehicle, and why do you want it to ignore that?
In my case, the ROV is disturbed either by tension on its tether or by the passage of a nearby motorboat. For my application the ROV needs to maintain as still as possible in order to take acoustic measurements, so I would like it to maintain its target depth as consistently as possible, even when subjected to external disturbances like that.
The firmware has protections against automated futile running of the thrusters when it expects the vehicle has run into the bottom or surface..
I’m unsure whether the position controller has its own limits on how long it’s happy to push in a direction without making progress.
If I understand correctly, the ROV changes its target depth when its detects that it has reached the surface or the bottom.
Just to be sure, do you know if it determines this only through its depth sensor? For the surface I believe the SURFACE_DEPTH parameter which defines the depth at which the ROV considers itself at the surface, is that correct ?
In my logs, I see EV_BOTTOMED message appearing but with only a depth sensor, the ROV shouldn’t be able to know if it’s at the bottom.
These messages are probably sent also if, as you mentioned, there are internal limits on how long or how strongly the controller tries to reach the target.
The depth target is handled the same in the autopilot, regardless of whether it is set by manually piloting to the desired depth, or commanding the depth with a script.
Thanks is very helpful!
I will keep trying with a script to see if it can avoid this behavior for the kinds of disturbances. Feel free to let me know if you think of another approach
The ideal, of course, is to minimize disturbances as much as possible in the first place but in marine environment, it’s always tricky
I see. I wouldn’t expect passing boats to cause substantial / long-duration disturbances to the depth, and if you’re attempting to maintain a stable position it seems problematic for the tether to be taught enough to be causing disturbances from its tension.
Here is the surface and bottom detection code. It even attempts to detect those states when there’s no depth sensor attached, using a velocity estimate.
Yes, that’s what surprised me too - that a nearby motorboat passing could cause a long enough disturbance to make the ROV lose its position. With all your helpful clarifications about this behavior, I will able to check this more carefully in my next tests.