Send velocity and angular velocity command dynamically

I want to dynamically instruct velocity and angular velocity to BlueROV by python program.
I think set_target_depth in Pymavlink is one solution, but it maybe not finish until reach to target position. (Is it correct?)

Initial status is vx=0.0(m/s) yaw-rate=0.0(rad/s)
If I am about to change the status to vx=0.5, yr=0.5 (real-status 0.3, 0.3) and then want to change it to 0.0, 0.0, is it possible to execute a new function during the execution of the function?
If not, what is the solution?

I will change type_mask in set_target_depth
uncomment
・mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE
・mavutil.mavlink.POSITION_TARGET_TYPEMASK_FORCE_SET
commentout
・mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE
・mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE
First of all, is it correct?

Hi @yuki,

The SET_POSITION_TARGET_GLOBAL_INT MAVLink message (which is used in our example set_target_depth function) sets the current target for the vehicle to aim for - there’s no requirement to meet/achieve the current target in order for a new target to be specified instead.

That said, using that message currently requires a position-enabled flight mode (like Depth Hold, if you only want to control vertical position, or Guided mode if you want to target horizontal positions/velocities as well), which means it requires a position estimate (from a barometer for depth; or from a DVL, underwater GPS, etc for horizontal control).

Given you’re trying to control horizontal velocity, if you have a positioning sensor then it should work to set velocity targets if you want to, while in guided mode. The current ArduSub implementation requires setting all three (x,y,z) velocity targets together, because if you ignore one it will ignore all of them.

Changing the acceleration commands into force commands is not relevant here, but also wouldn’t work. The force, yaw, and yaw rate options are not currently implemented.


All up,

  1. If you have a (horizontal) position estimate
  2. And your vehicle is in Guided flight mode
  3. You can use the SET_POSITION_TARGET_GLOBAL_INT message to set velocity targets
  4. Which should use the following bitmask
    type_mask=( # ignore everything except velocity targets
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE |
        # DON'T mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |
        # DON'T mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |
        # DON'T mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE |
        # DON'T mavutil.mavlink.POSITION_TARGET_TYPEMASK_FORCE_SET |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE |
        mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE
    )
    
  5. And should set targets for all of vx, vy, and vz.

Thank you for your reply.

I think we can control the horizontal velocity (vx, vy, vz) in GUIDED mode.
In conclusion, is it impossible to control vx and yaw-rate simultaneously?

Hmm, that does seem to be the case if you want to use ArduSub to do the control for you (by setting targets for it to follow). I’m unsure whether it would be difficult to add yaw rate control as an option.

If having control of forward velocity and yaw-rate is important you could either modify ArduSub, or create your own external control loop via pymavlink that uses the telemetry information to determine which control commands to send. It would be more efficient and effective to do in ArduSub, but it’s possible an external approach would be simpler to implement.

I will try to implement to control ROV by PWM input.
It shows relationship between the PWM Input value and Thust force.
Do you know any implementation to control ROV form PWM input value.

Our thrust vs input signal curves likely do not hold precisely for thrust at speed.

If you’re targeting a specific desired velocity, and you have an estimate of current velocity and a method to tell the vehicle to move faster or slower, you can implement whichever control algorithm you like to control the vehicle commands based on the “error” between the desired and current velocity.

Depending on your precision and transfer time requirements different approaches may or may not be sufficient for your purpose.

A reasonably simple approach is to use just proportional control, where if the error is large you apply a large control action (e.g. if you are much slower than desired you significantly increase the commanded throttle), and if the error is small you apply a small (or zero) control action (change the commanded throttle by a small amount, or leave it as is). The amount to change by is determined by the error multiplied by a scaling factor, which is a parameter of the algorithm that you can tune.

If you need more advanced control you can use a full PID controller (proportional, integral, derivative), which is still reasonably simple (and will have many implementations available online), but has some additional tuning parameters that help to dampen oscillations and correct for long duration small errors.

Beyond that you could potentially go to a more advanced controller, but if that’s deemed to be necessary then it’s almost certainly worth implementing the control within ArduSub instead, since it has access to much higher sensor measurement frequencies, and can apply control actions with lower latency.

I’m going to try to implement 6-DoF Modelling and Control of a Remotely Operated Vehicle with this as a reference for now.
Do you know how much some parameters (e.g. inertia moment ) in the kinetic model should be?
I have a BlueROV heavy coniguration with various things attached like scanning sonar, waterlinked DLV, payloads kid, etc. so it might be very different from the original state.
Or do you know how to measure these parameters?

If all you’re after is velocity control, this seems like way more effort than should be necessary.

There’s some discussion of the parameters in this thread. Blue Robotics has not done measurements of them, and correct values would depend on the vehicle configuration in use (including added components).

If there are specific parameters you’re interested in and can’t readily find out how to estimate we can try to discuss them. Some may have already been discussed in posts with the vehicle-design tag. Some may be challenging to measure without specialised equipment, and may require fluid simulation software to estimate accurately.

1 Like

In this post, you say that it is not sure if can control multiple thrusters at once by using MAV_CMD_DO_MOTOR_TEST .

Do you konw how to send PWM to multiple thrusters at once?

I try to rotate the thruster by sending PWM value with MAV_CMD_DO_MOTOR_TEST , but the thruster do not rotate. (channel 1-8)
when I try to bright the light in the same way, I can change the brightness.(channel 9)
How can I solve it?

I can rotate thruster by using RC_CHANNELS_OVERRIDE.

Normally you would use RC_CHANNELS_OVERRIDE or MANUAL_CONTROL messages, although it’s technically also possible to use MAV_CMD_DO_SET_SERVO if you configure the motor outputs as “Disabled” in the SERVOn_FUNCTION parameters (instead of their usual MotorN values), as I mentioned in the post you linked to (with the caveats mentioned there).

If you wanted to try it with MAV_CMD_DO_MOTOR_TEST I imagine you would just need to send multiple in short succession, but I don’t know if it would work and haven’t tried. That message is also not intended for general motor control, so if it does work at the moment that doesn’t guarantee it would continue working in future, so it’s not an approach I’d recommend if other options are also available.