RC_OVERRIDE/ MANUAL_CONTROL not working mavlink

Hi, I am attempting to manually control the blueROV2 with a Jetson Nano connected over the Telem 2 port of the Pixhawk. I am using mavsdk and c++ to do this. I have also tried to use Python just to get it working, but no luck with either.

I am able to do things such as arm/disarm, request messages such as NAV_CONTROLLER_OUTPUT through Python or C++, but I cannot get the motors to respond to a manual control or RC_override command.

Here is an example of my C++ functions for RC_Override and Manual Control.

bool send_rc_override(MavlinkPassthrough &_mavlink_pass){
    mavlink_message_t message2;
    qDebug() << "System ID" << QString::number(_mavlink_pass.get_our_sysid()) << "\n" <<
              "Comp ID" << QString::number(_mavlink_pass.get_our_compid()) << "\n" <<
              "Target ID" << QString::number(_mavlink_pass.get_target_sysid()) << "\n" <<
              "Target Comp ID" << QString::number(_mavlink_pass.get_target_compid()) << "\n";

    mavlink_msg_rc_channels_override_pack(_mavlink_pass.get_our_sysid(),
                                      _mavlink_pass.get_our_compid(),
                                      &message2,
                                      _mavlink_pass.get_target_sysid(),
                                      _mavlink_pass.get_target_compid(),
                                      1450,
                                      UINT16_MAX,
                                      1450,
                                      UINT16_MAX,
                                      UINT16_MAX,
                                      UINT16_MAX,
                                      UINT16_MAX,
                                      UINT16_MAX,
                                      UINT16_MAX-1,
                                      UINT16_MAX-1,
                                      UINT16_MAX-1,
                                      UINT16_MAX-1,
                                      UINT16_MAX-1,
                                      UINT16_MAX-1,
                                      UINT16_MAX-1,
                                      UINT16_MAX-1,
                                      UINT16_MAX-1,
                                      UINT16_MAX-1);

    if (_mavlink_pass.send_message(message2) == MavlinkPassthrough::Result::Success){
        qDebug() << "Successfully sent RC message \n";
    }
    return true;
}

bool send_manual_control(MavlinkPassthrough &_mavlink_pass){
    mavlink_message_t message1;

    mavlink_msg_manual_control_pack(_mavlink_pass.get_our_sysid(),
                                          _mavlink_pass.get_our_compid(),
                                          &message1,
                                          _mavlink_pass.get_target_sysid(),
                                          400,
                                          400,
                                          400,
                                          400,
                                          0,
                                          0,
                                          0,
                                          0,
                                          0);


    if (_mavlink_pass.send_message(message1) == MavlinkPassthrough::Result::Success){
        qDebug() << "Successfully sent RC message \n";
    }

    return true;
}

These functions are run after creating a MavlinkPassthrough instance such as

auto mavlink_pass = MavlinkPassthrough{system};

When doing manual control, I can even see in QCGround Control that the manual control message is being received with my given parameters, but the motors are not responding.

With my Python code, I can do something like this

# Import mavutil
from pymavlink import mavutil
import time

master = mavutil.mavlink_connection("/dev/ttyACM0", baud=115200)

# Wait a heartbeat before sending commands
master.wait_heartbeat()
print("Heartbeat Heard")

heartbeat = mavutil.periodic_event(1)
motor = mavutil.periodic_event(0.1)
start = time.time()
duration = 160 # seconds

while (time.time() - start < duration):
	if heartbeat.trigger():
		master.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_GCS, 
					  mavutil.mavlink.MAV_AUTOPILOT_INVALID,
					  0,0,0)
	if motor.trigger():
		master.mav.manual_control_send(
		    master.target_system,
		    0,
		    0,
		    490,
		    0,
		    0)
		print("count")

and I can see the output in QCGround Control for a second or so, then the messages stop sending and the code freezes.

I am really concerned that my serial buffer is getting overloaded or something. I have no clue where to go with this from here. Hopefully, someone has a suggestion.

Also, note that I arm the vehicle manually for the python code as sometimes it arms and sometimes it does not.

I also run the C++ send message function in a loop, so its not that I am only sending it once

Update:

To add a few more details from my investigation today, I can successfully connect the Jetson Nano over Ethernet like a topside computer and run a Python/c++ script and command the motors successfully over udp. But if I run the same Python/c++ scripts over usb connection to Telem 2 of the pixhawk, the motors run for 1.4-1.6 seconds then the script freezes and stops sending messages. If I ctrl-C out of the Python script, it is getting hung up on line 993 of mavutil.py

return self.port.write(bytes(buf))

Pretty sure this means my serial port buffer I having issues. Hope this is helpful

Hi @cmarq,

From your latest update, it seems

  1. The control you’re trying to achieve works from the topside computer
  2. The same control works via the telemetry port, but stops after a short period

which are useful details to have established.

It’s possible there are serial port issues, although given the low frequency you’re sending messages relative to the baudrate it seems unlikely there would be a send buffer that’s full enough to block further messages in.

A couple of suggestions:

  1. Does it help to change QGC’s System ID to a non-255 value (in Application Settings/MAVLink), or just to not have QGC open?
    • It’s possible that having QGC connected with the standard ground controller System ID and sending control commands at the same time is causing issues
  2. Does it help to read some serial data (e.g. perhaps wait for a heartbeat every time you send your own heartbeat)?
  3. To help debug, can you add some print statements to the loop (or just count how often messages are sent vs the expected frequency)?
    • That should help determine whether the code is actually stopping execution from some block, or it’s running as normal and the autopilot is just ignoring inputs after some point (due to some parameter or other interference)
  4. It may be help to add a short time.sleep within the loop (e.g. 10ms), although that’s more to reduce excessive CPU usage since the periodic events should avoid overloading the serial buffer

You should be able to arm with master.arducopter_arm(), and confirm it with master.motors_armed_wait() (as done here). If that’s not working consistently then you may be losing some messages, in which case it may help to send a few arm messages before waiting for arming to be confirmed.

Hi Eliot,

I was able to figure out a solution after reading your thoughts. In my C++ code, I found that if I sent the mavlink message to control the motors with the sys_id of the Jetson nano, it was sending as ID 245. As you know, the ID of the GCS is 255. There is a line of code in Ardusub that says to ignore any incoming manual_control messages if the ID is not 255. So from my C++ code, the ROV was quietly denying my messages. They would show up in QGC, but no change in the RC output would happen.

I am still unsure what the issue is for my Python script, but my goal is to use C++, so I am not going to pursue that further.

1 Like