Custom 5-Thruster Configuration for BlueROV2 - Stability Issue in Stabilize/Depth Hold Modes

Hello Blue Robotics community,

I’ve been working on a project with the BlueROV2 that requires a 5-thruster configuration. Our custom configuration, motor matrix, and frame design are shown below. As you can see, we disabled the 6th thruster, which is temporarily strapped to the center of the ROV.

We successfully flashed the custom firmware with our motor matrix, and the ROV operates reliably in manual mode. However, we encountered a critical issue when switching to Stabilize or Depth Hold modes. In these modes, the ROV starts flipping uncontrollably, rendering these features unusable.

Troubleshooting So Far:

  1. We ran the motor direction test and consistently failed on Thruster 4 (one of the two rear vertical thrusters).
  2. To rule out hardware issues, we reassigned Thruster 4 to a different motor in the firmware, but the issue persisted.
  3. Returning to the default 6-thruster configuration confirmed that the ROV operates correctly with the predefined setup, including Stabilize and Depth Hold modes.


Suspected Issue:

From our observations, we believe the problem lies in how the pitch and roll values are defined in the custom motor matrix. While the ROV functions well in manual mode (where pitch and roll are not actively controlled by the default controller setup), these parameters are critical for Stabilize and Depth Hold modes. The instability suggests that the custom motor matrix may not be correctly balancing forces or responding appropriately to pitch and roll feedback.

Questions:

  1. How should we assign values in the custom motor matrix to account for pitch and roll stabilization?
  2. Are there specific guidelines or examples for defining motor matrices for custom configurations like ours?

Any advice or insights from those who have worked with custom thruster configurations or modified BlueROV2 firmware would be greatly appreciated.

Thank you for your time!

Hi @Matthue -
Welcome to the forums!
The issue you’re having is definitely related to the vehicle configuration being incorrect - either the thruster matrix, or your autopilot orientation (likely not the latter as you’re keeping it default for BROV2, roll 90?)

Your breakdown table and diagram are incredibly confusing! Can you share just the code that you modified with the thruster matrix? That may be a clearer way of relating the changes you made.
Each thruster in the matrix is supposed to have its contribution to roll, pitch, yaw and depth attributed to it. Your thruster configuration also doesn’t seem to match your diagram, as the vertical thrusters are flipped from the arrangement you show (two in front not back.)

The change in layout is interesting, I’d be curious what’s motivating you to explore the alternative arrangement?

Hi Tony,

Thank you for your response and for pointing out the potential configuration issues—your input is very helpful!

I completely understand that the diagram is confusing and could have been clearer. This project is a collaborative effort, and I would have preferred a simpler diagram as well. To clarify, the diagram is consistent with the physical layout of our ROV. However, there is a discrepancy between the hardware motor numbering on the ROV and the firmware definitions, and I’m honestly not sure how that mismatch came to be. The red arrow in the diagram is intended to indicate the forward direction of the ROV, which features one vertical thruster at the front and two vertical thrusters at the rear. Also, note that the sixth motor is still physically connected but disabled in our firmware. It’s temporarily secured to the center of the frame with a zip tie while we develop our custom configuration and work with the hardware we currently have. We do, in fact, have a vertical motor mounted to the front via a 3d printed mounting jig that covers the front camera.

We agree that the issue stems from the thruster matrix, and we haven’t made any changes to the autopilot orientation (which is still set to the default for the BlueROV2, roll 90).

The motivation behind the alternative thruster arrangement is that our project requires active self-leveling, which isn’t possible with the default 6-thruster configuration. The standard layout doesn’t allow for independent pitch control due to only having two vertical thrusters.

After investigating the ArduSub source code, specifically the directional motor test logic, I started wondering if the two rear thrusters might inherently contribute to yaw due to motor rotation. Part of the failure in the motor test might stem from the fact that we haven’t assigned a yaw parameter for these thrusters in our motor configuration matrix.

Unfortunately, I don’t have access to the exact source code we used to modify the firmware at the moment. However, the relevant section of the code defining our custom frame is as follows, which should align with the table in my original post and the motor numbering in red:

case SUB_FRAME_CUSTOM:
    _frame_class_string = "CUSTOM";
    add_motor_raw_6dof(AP_MOTORS_MOT_1,  0,    -1.0f,   0,    0.53f,   0,   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,      1.0f, 0,     1.0f,  0,   3);
    add_motor_raw_6dof(AP_MOTORS_MOT_4,  0.5f, -0.5f,   0,    0.45f,   0,   0,   4);
    add_motor_raw_6dof(AP_MOTORS_MOT_5, -0.5f, -0.5f,   0,    0.45f,   0,   0,   5);
    break;

If there’s anything glaringly wrong in how we’ve defined this matrix, I’d greatly appreciate your insights! Additionally, do you think the lack of a yaw parameter for the rear thrusters could explain why the motor test is failing?

Looking forward to hearing your thoughts—thanks again for your time and expertise!

Hi @Matthue -
Just a quick glance at our documentation on this shows that you may have a lot of numbers wrong. The example we give is for a very similar thruster layour, with only the position of the vertical thrusters different than your own?

Ignoring thruster 6, motors 1 & 2 should have the full 1/-1 yaw and forward factor.

Motors 3 & 4 contribute equal amounts to the roll and pitch factor - I suppose both of your pitch factors are negative because you’ve placed the thrusters on the opposite end of the vehicle?

Thruster 5 may need to be higher, 1.0, to balance the sum of the 3&4 throttle factors?

I don’t think the yaw moment of the rear thrusters would explain why the motor tester is failing…that said, verifying your thrusters direction manually for the custom frame may be preferable - if it’s correct in manual mode and things go crazy in stabilize, then the problem rests with the thruster matrix, and not the set direction.