Simple ROV 3 Frame problems

Hi, We are having some problems with the Simple ROV 3 Frame in Ardusub and hope you can offers some suggestions to mitigate the problem. We have been using the Simple ROV 3 Frame for our Barracuda vehicle which has 2 T200 motors mounted outboard on the dive planes for yaw and forward/reverse thrust, and an internal counterweight to control pitch. We are using an XBox controller for control when tethered.

We have seen a couple of abnormal behaviors some minor and some more critical.

First, when I go through the calibration routine for the controller. I set the left joystick for throttle and yaw control. I set the right joystick for pitch. When we run the vehicle the left stick is pitch and yaw and the right stick is throttle.

I think that this is an artifact from Ardupilot where throttle controls altitude for an aerial drone and pitch controls forward and reverse motion. Once we realized that this was happening it was simple to manage in ROV mode.

The problem is more serious when we attempt an autonomous mission. We can set waypoints and the vehicle attempts to perform the mission but it acts like it cannot resolve the pitch control or control depth.

When I look at the Simple ROV 3 Frame I see that there is no pitch component and thrust is assigned to motor 3. Again this is because throttle controls altitude in aerial drones and so in this frame it is expected that motor 3 controls depth. I have attached an image of the frame here for reference.

case SUB_FRAME_SIMPLEROV_3:
        _frame_class_string = "SIMPLEROV_3";
        add_motor_raw_6dof(AP_MOTORS_MOT_1,     0,              0,              -1.0f,          0,                  1.0f,               0,              1);
        add_motor_raw_6dof(AP_MOTORS_MOT_2,     0,              0,              1.0f,           0,                  1.0f,               0,              2);
        add_motor_raw_6dof(AP_MOTORS_MOT_3,     0,              0,              0,              -1.0f,              0,                  0,              3);
        break;

So, the solution seems to be to create a custom frame. The question I have is should motor 3 be throttle AND pitch or should it be pitch only. Can the AHRS be able to resolve that pitch controls depth in our vehicle?

Hi @lunarminer -
A custom frame is likely necessary, but if your pitch is linked to depth because you need to pitch to an angle to descend, I’m afraid ArduSub may inherently not be able to understand that… As it was originally forked from ArduCopter, and quadcopters don’t pitch to control altitude!

Some pictures of your vehicle may be helpful if I’m misinterpreting your mode of operation.

Hi Tony, yes the vehicle needs to pitch down and up to descend and ascend. I was afraid that might be the case. If a custom frame doesn’t work then we’ll most likely have to use Ardurover to maneuvers in the XY plane and use the companion computer to control pitch, depth, and altitude above the bottom.
Here is a picture of the current state of the vehicle. The counter weight internally is the battery and we use a linear actuator to move it.

Hi @lunarminer -
Very cool vehicle! I’m surprised you use both the nozzles and the guards, do you operate in areas with a high risk of loose material like fishing line? If not, I think you’re really impacting your efficiency pretty radically!

I wonder if ArduPlane may be a good fit for this system :thinking: Maybe a question for the ArduPilot forums? I believe they might even have navigation without GPS input? Maybe @EliotBR has some ideas? If not, you could tow a buoy with GPS during development of whatever additions to go without position sensor (assuming that’s not a DVL on the tail?)

Thanks for sharing :smiling_face_with_sunglasses:

Hi, the grills are removable. We do a lot of testing in a freshwater lake that has a lot of water plants. So, we use the grills.

Hi @lunarminer, cool application!

As @tony-white mentioned, ArduSub is not really set up to handle this kind of hardware - it would fall under the advanced control options that we’re aware of as ideas but haven’t yet been implemented in ArduSub[1].

ArduSub’s motor motion axis contribution factors are used to specify how much each motor output should change when processing commanded movements across one or more motion axes, or how they should be set directly when in manual mode.

If you’re able to assume your vehicle will always have some forwards thrust (or momentum) when it needs to pitch or move vertically, then it could be sufficient to specify motor 3 as controlling both throttle and pitch, although behaviour may not be optimal (it does seem worth a try, at least!).

If your vehicle sometimes needs to move backwards and vertically while operating in an automated/stabilised control mode then I expect ArduSub’s current feature set won’t be sufficient for your use-case, although it could be workable if that only needs to happen in manual or acro mode :slight_smile:

Using ArduPlane and pretending your movable mass is in fact a pitch-focused control surface is likely the closest you could get to properly designed control of your vehicle with an existing ArduPilot firmware. That said, using ArduPlane effectively underwater may require some modifications.


  1. It currently assumes every motor is a statically-positioned thruster. ↩︎