MANUAL_CONTROL axes and heavy config

Hello,

I’m trying to set up a Python script to drive the BlueROV2 in response to inputs from an experimental haptic controller but am getting weird outputs to the MANUAL_CONTROL messages. My understanding is that the axes you can control in the message are as follows:

  • x = pitch
  • y = roll
  • z = forward/reverse
  • r = yaw

However, whichever of these axes I set (and make the others 0) only the 4 vertical thrusters spin up. I cannot get the other thrusters to move at all. I am using the heavy configuration of the ROV so don’t know if this has to be specified anywhere in the parameters or if the different thruster setup on the heavy changes how I should use this message. I have set the heavy frame in QGC which I assume means it is set on the ROV but I could have misunderstood this?

Any advice would be appreciated. I’ve copied my code (basically stitched two examples together) below.

from pymavlink import mavutil

master = mavutil.mavlink_connection('udpin:0.0.0.0:14550')
master.wait_heartbeat()
print("Connected!")

# Arm
# master.arducopter_arm() or:
master.mav.command_long_send(
    master.target_system,
    master.target_component,
    mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
    0,
    1, 0, 0, 0, 0, 0, 0)

# wait until arming confirmed (can manually check with master.motors_armed())
print("Waiting for the vehicle to arm...")
master.motors_armed_wait()
print('Armed!')

master.mav.manual_control_send(
master.target_system,
100,
0,
0,
0,
0)
master.wait_heartbeat()

# Disarm
# master.arducopter_disarm() or:
master.mav.command_long_send(
    master.target_system,
    master.target_component,
    mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
    0,
    0, 0, 0, 0, 0, 0, 0)

# wait until disarming confirmed
print("Waiting for the vehicle to disarm...")
master.motors_disarmed_wait()
print('Disarmed!')

Hi @JPB515, welcome to the forum :slight_smile:

That’s not correct. The mapping is described here, except that the s and t axes are not yet available in ArduSub, so those roles are instead taken on by the x and y axes when the ‘roll/pitch toggle’ joystick functionality is toggled from forward/lateral mode to roll/pitch mode.

Yes, setting the frame in QGC should set it in the ROV’s firmware. If you open QGC and the vehicle shows up as having the heavy frame then it is currently configured that way in the vehicle (QGC does not store that configuration anywhere, just reads it from the vehicle parameters).

That seems odd. A couple of questions:

  1. Does the motor test page allow you to test each of the motors individually?
  2. Does the vehicle work as expected when you’re controlling it with a joystick through QGC?

Thanks for the detailed reply! It looks like I was using the documentation for the MANUAL_CONTROL message which uses rotational rather than directional control:

https://mavlink.io/en/messages/common.html#MANUAL_CONTROL

I can control each of my motors using the motor test page in QGC and with the resources you linked (and another pair of eyes on the robot) it looks like running

master.mav.manual_control_send(
    master.target_system,
    300,
    0,
    0,
    0,
    0)
master.wait_heartbeat()

spins up all 8 thrusters, instead of just 1-4. Waiting a few seconds and calling

master.mav.manual_control_send(
    master.target_system,
    0,
    0,
    0,
    0,
    0)
        master.wait_heartbeat()

turns 1-4 off but leaves 5-8 on for another second or two. I assume these then get turned off via some sort of timeout or error as it then takes two attempts to arm the robot the next time I run my code. I’ve got to the point where this behaviour is at least reliable, so I’m hoping there’s something easy going on that I’ve misunderstood from the docs.

It’s unclear why 5-8 are staying on after you command a stop, but it’s quite likely you’re correct as to why they’re being turned off.

Do you know if your vehicle is operating in manual mode? If it’s in an actively controlled flight mode like depth hold or stabilize then zeros as control input may be interpreted as “maintain this” rather than “stop moving”.

It should at minimum work to disarm when you’re done if you want a more immediate stop, but it would likely be useful to determine what’s causing the unexpected behaviour and stop it at its source.

Alas, no. I’ve set up a thread sending heartbeat messages ~every 0.75 seconds. Can also confirm I’m now sending the mode change to manual and receiving acknowledgement each time I run the program (instead of assuming it was saved from QGC).

I’ve cut my program down to a minimal example that shows some of what’s going wrong. The below code should run thrusters 1-4 for 5 seconds, stop, run 1-4 again for 5 seconds (in reverse), then stop again and disarm.

import sys
import time
from pymavlink import mavutil
import threading

def heartbeat_helper(master):
    print('start heartbeat thread')
    while True:
        master.mav.heartbeat_send(6, 8, 128, 0, 0)
        print('sent heartbeat')
        time.sleep(0.75)


#Connect to blueROV2 over MAVlink
master = mavutil.mavlink_connection('udpin:0.0.0.0:14550')
master.wait_heartbeat()
print("Connected to robot!")

#Start heartbeat thread
heartbeatThread = threading.Thread(target=heartbeat_helper, args=(master,))
heartbeatThread.daemon = True
heartbeatThread.start()

#Set robot mode

# Choose a mode
mode = 'MANUAL'

# Check if mode is available
if mode not in master.mode_mapping():
    print('Unknown mode : {}'.format(mode))
    print('Try:', list(master.mode_mapping().keys()))
    sys.exit(1)

# Get mode ID
mode_id = master.mode_mapping()[mode]

# Set new mode
master.set_mode(mode_id)

while True:
    # Wait for ACK command
    ack_msg = master.recv_match(type='COMMAND_ACK', blocking=True)
    ack_msg = ack_msg.to_dict()

    # Continue waiting if the acknowledged command is not `set_mode`
    if ack_msg['command'] != mavutil.mavlink.MAV_CMD_DO_SET_MODE:
        continue

    # Print the ACK result !
    print(mavutil.mavlink.enums['MAV_RESULT'][ack_msg['result']].description)
    break

master.wait_heartbeat()

# Arm
# master.arducopter_arm() or:
master.mav.command_long_send(
    master.target_system,
    master.target_component,
    mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
    0,
    1, 21196, 0, 0, 0, 0, 0)

# wait until arming confirmed (can manually check with master.motors_armed())
print("Waiting for the vehicle to arm...")
master.motors_armed_wait()
print('Armed!')

print("Forward")
master.mav.manual_control_send(
    master.target_system,
    300,
    0,
    0,
    0,
    0)
time.sleep(5)

print("Stop")
master.mav.manual_control_send(
    master.target_system,
    0,
    0,
    0,
    0,
    0)
time.sleep(3)

print("Reverse")
master.mav.manual_control_send(
    master.target_system,
    -300,
    0,
    0,
    0,
    0)
time.sleep(5)

print("Stop")
master.mav.manual_control_send(
    master.target_system,
    0,
    0,
    0,
    0,
    0)
time.sleep(3)

# Disarm
# master.arducopter_disarm() or:
master.mav.command_long_send(
    master.target_system,
    master.target_component,
    mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
    0,
    0, 21196, 0, 0, 0, 0, 0)

# wait until disarming confirmed
print("Waiting for the vehicle to disarm...")
master.motors_disarmed_wait()
print('Disarmed!')

What is actually happening is this spins 1-8 for about 2.5 - 3 seconds, then turns everything off for about 10 seconds and then disarms the robot. My guess/assumption is that the messages are still getting through to the robot but there is some condition stopping them from executing.

Disarming definitely works to turn everything off for safety/E-stop purposes, but without robust control over the thrusters in each direction I can’t claim to have reliable motion control.

Not really sure what’s going wrong here.

Can you try using RC_CHANNELS_OVERRIDE messages instead of MANUAL_CONTROL, and/or try this example? ArduSub effectively uses manual control messages as an abstraction over rc overrides anyway, so there’s one less thing in between that may be causing issues.

Note the clear_motion calls in the example before arming (that has helped resolve some issues previously). Also, can you specify the versions of the softwares you’re running (ArduSub (on Pixhawk/Navigator?), Companion/BlueOS, QGC, pymavlink)?

That was interesting…

RC control is sort of working - I can isolate directions much better, but channel 3 (supposedly throttle) still spins the vertical thrusters. Channel 5 (forwards) does actually work correctly, so that seems to be ok for now as a work around. Might explain the behaviour I was seeing with MANUAL_CONTROL, though would be nice to know why this isn’t working as expected.

My software versions are ArduSub 4.1.0 (running on a Pixhawk), Companion 0.0.31 and pymavlink 2.4.31. QGC is working fine but is at version 4.2.3. I know ArduSub is out of date but I have a very weak internet connection to the robot (the Pi can’t connect to my uni wifi network) and so get timed out whenever I try to update.

Throttle is the vertical control, so that is expected.

4.1.0 is our latest stable ArduSub version, so that’s not out of date. Our Companion software is no longer being developed though - you may wish to try out BlueOS.

On the updating ArduSub front, if you have a slow internet connection to your Raspberry Pi you should still be able to download ArduSub firmware to your topside computer and do a direct upload of that to your autopilot board via the web interface of your Raspberry Pi software.