Custom Thruster configuration

Hello.
This is my first post I hope I’m posting in the right place. I’m building an ROV with 6DOF with 8 thrusters. I will try to explain my thruster setup.

4 vectored thrusters on the bottom of the ROV which, if standing on a table controls yaw, forward/backward and lateral movement.

And then, above them. There are 4 other vertically vectored thrusters, which controls depth, pitch and roll. I’ve been viewing the ROV setups here: Features · GitBook

But I’m wondering how the software will determine which thruster is which when my thrusters are placed above eachother?

Hello Max,

I’m not sure I understood your setup 100%, it sounds to me a lot like our Vectored ROV w/ Four Vertical Thrusters, except for the vectored thrusters. As this already gives us 6 degrees of freedom, why do you need vectored thrusters?

Unfortunately there is no support in ArduSub for them. ArduSub works by giving factors for each movement to each thruster (see here), and vectored thrusters can’t be described like that properly.

The software doesn’t know where the thrusters are, it only knows what they are supposed to do (speeding up thrusters 6 and 8 will cause the vehicle to roll right, speeding up 5,6,7 and 8 will cause it to go up…), that is why it is so important during setup that all the thrusters are mounted correctly and spinning the right direction.

Thanks for the quick response. I would imagine the arengement would look something like this: Self-Stabilization Control Mechanism For a Small ROV Sea Technology magazine

The top thrusters being vectored as well.

Hi Max,

you can get more information about it in our custom configuration documentation and searching in the forum.

2 Likes

Yes I have searched and I understand how to make a new configuration. However, I am looking for an answer if the thruster setup I posted above is realisable with ardusub?

Hi Max,

The frame that you shared in the Sea Technology link is essentially the same as the ArduSub “Vectored ROV w/ Four Vertical Thrusters” frame type, which we use on the BlueROV2 Heavy configuration.

You can use that frame type directly without any customization. The thrusters are numbered and must be connected to the Pixhawk autopilot in that order. Here’s the numbering for this configuration:

image

I hope that helps! Good luck with your vehicle build and feel free to post any other question you have!

-Rusty

1 Like

Thanks. That’s a good start. However, as the placement of the top thrusters on the Rov I linked can help slightly in forward/reverse and lateral movement as well as vertical movement, wouldn’t it be good to assign these parameters to them too? Maybe just make them have a lesser value in the forward/reverse and lateral direction? What do you think?

Hi Max,

The top thrusters in this configuration can contribute to forward/backward and lateral movement since they are tilted a little bit but I don’t think you’d want to use them for that as they are coupled to other motions that you don’t want. For example, if you used the top thrusters to help move forward, it would also cause the vehicle to pitch nose down.

The reason for the tilted thrusters on this frame is to prevent the flow from hitting the foam on the bottom of the ROV, not to contribute to the dynamics. I think the frame type that is already in ArduSub is optimal for this configuration.

-Rusty

1 Like

I understand what you mean. But, like the ROV I posted, I have a foam block on top and bottom wouldn’t it be best to have vectored top thrusters as well? I’ve looked at the OceanBotics SRV8 too and they seem to have all thrusters vectored in some manner.

I would assume that having all thrusters vectored would give the ROV roughly the same performance in X, Y and Z movement?

Assuming I have vectored thrusters as the ROV I posted before, should I for example, set the forward parameter of one of the top thrusters to say, 0.25f? Does this mean that the forward contribution of that thruster is 25 %? Or how do I interpret these parameters?

Thanks for all the quick responses, much appreciated.

1 Like

I’ve done a simple drawing showing how I plan to put my thrusters. Looking at the drawing, assuming a forward direction (1) would create an upward movement/force (2) as the bottom thruster isn’t put in the center of mass. If the top thrusters are then placed as in the picture, they would counter this upward force (4) and still produce forward movement (3). This would also be true if the ROV moved in a lateral direction.
What do you think about this? I plan to mount 4 thrusters like this in the top and then 4 at the bottom. The bottom ones being mounted as is in the model posted by you previously. I’m a little bit unsure how to set the parameters for those top thrusters in the CUSTOM_FRAME. Any help would be appreciated.

Forces.pdf (52.2 KB)

Hi Max,

Okay, if you have foam on top and bottom then I would also tilt the thrusters outward to give the thrusters a clear path.

Looking at your diagram I understand what you’re thinking. You’re correct that the upward pitching force (2) would counter the downward pitching force (3) and (4). However, these effects have to be perfectly tuned or you’ll end up with a very wobbly vehicle. Any changes to the vehicle, like an added payload, would require retuning.

Because of that, I would still leave the forward and lateral contributions of those thrusters at zero. But, if you’re interested in trying, you can start off by modifying the Roll Factor and Pitch Factor of thrusters 1-4 in the frame configuration:

// Motor #                         Roll Factor     Pitch Factor    Yaw Factor      Throttle Factor     Forward Factor      Lateral Factor  Testing Order
case SUB_FRAME_VECTORED_6DOF:
add_motor_raw_6dof(AP_MOTORS_MOT_1,     0,              0,              1.0f,           0,                  -1.0f,              1.0f,           1);
add_motor_raw_6dof(AP_MOTORS_MOT_2,     0,              0,              -1.0f,          0,                  -1.0f,              -1.0f,          2);
add_motor_raw_6dof(AP_MOTORS_MOT_3,     0,              0,              -1.0f,          0,                  1.0f,               1.0f,           3);
add_motor_raw_6dof(AP_MOTORS_MOT_4,     0,              0,              1.0f,           0,                  1.0f,               -1.0f,          4);
add_motor_raw_6dof(AP_MOTORS_MOT_5,     1.0f,           -1.0f,          0,              -1.0f,              0,                  0,              5);
add_motor_raw_6dof(AP_MOTORS_MOT_6,     -1.0f,          -1.0f,          0,              -1.0f,              0,                  0,              6);
add_motor_raw_6dof(AP_MOTORS_MOT_7,     1.0f,           1.0f,           0,              -1.0f,              0,                  0,              7);
add_motor_raw_6dof(AP_MOTORS_MOT_8,     -1.0f,          1.0f,           0,              -1.0f,              0,                  0,              8);
break;

-Rusty

Won’t the control system stabilizer and counter a wobbly Rov? Shouldn’t it do that in Acro mode as it would try to keep the attitude?

Do you mean modifying thrusters 5-8? Because 1-4 don’t affect pitch/roll do they?

@maxdrougge Why don’t you start with the provided option of vectored 6DOF and see if it meets your needs?

The control system will attempt to counter any coupling that is not accounted for, but that’s not an ideal situation.

I will definitely do that. I’m arranging a frame with foam blocks on top and bottom where I can mount the thrusters in whatever direction needs to be tested. The reason for double foam blocks is to make it unstable and use the control system for stabilization. What do you think about that?

If I were to want to power the Rov with a tether instead of batteries. Do you have any suggested DCDC (and ACDC top side) converter for the ROV? I suppose the higher voltage used will be better as the current going through the tether will be less and thus less power loss in the tether.

Hello again.
I can’t seem to activate acro-mode with my ardusub/pixhawk. Is this disabled or not supported? I would like to use acro-mode as this mode let’s the vehicle stay in a set attitude, correct?

If you are going to spend the majority of your time in the ‘normal’ orientation, then the static stability might be preferable. The thrusters can overcome that easily enough.

Powering a vehicle through the tether is dangerous and difficult. I recommend using a battery.

Acro stabilizes rate of rotation. Stabilize stabilizes angle. Acro is available with the other modes:

Thanks for the reply. I can’t activate the acro mode. It isn’t in the mode list you show on your pictures. How do I roll and pitch? There doesn’t seem to be any controls for it? Only forward, lateral, up, down and yaw?

Can you show me a screenshot of the modes not appearing in the list?

Make sure you are using the latest stable version of the software components listed on ardusub.com.

QGC only sends 4 analog axes to the vehicle at a time. The only way to accomplish roll and pitch with QGC is to switch toggle two of the axes between commanding roll/pitch and forward/lateral, by setting up a joystick button with the ‘roll_pitch_toggle’ function.

I will submit one once I’m at my pc. So, to have it 6DOF I got to have this toggle switch? Is that what you do on your video when you are rolling and pitching?