How to stop an RC channel override from Dronekit-Python

Hello! I’ve been working on RC_CHANNELS_OVERRIDE for my project for a few days. Basically, I want to implement this python code where it’s supposed to follow the marker by non-GPS navigation. I have my raspberry pi getting mavlink data stream from the Pixhawk.

To have the best accurate reading on the rover’s rotation, I used BNO055 and have it wired to an Arduino and connected it to my raspberry pi.

Here’s my code for the rotation where it takes the current reading of the angle_bno and the angle of the marker. Then it will stop when it reaches a certain difference between these angles. The angle_bno always starts at 0 from its reference

def arduino_bno(Angle, Angle_bno):

    while abs(Angle_bno - Angle) > 25:
        global Angle_bno
        if ((Angle > 0) & (Angle < 180)):
            vehicle.channels.overrides = {'1':1900} #Turn Right
        elif ((Angle > 180) & (Angle < 360)):
            vehicle.channels.overrides = {'1':1100} #Turn Left
        if ser.in_waiting > 0:  
            Angle_bno = float(ser.readline().decode('utf-8').rstrip())
        
        print("Angle: ", Angle, "   Angle bno: ", Angle_bno, "Circle x: ", circle_centerX, "Circle y: ", circle_centerY)
    time.sleep(1)
    vehicle.channels.overrides = {'1':1500}

My problem is that this while loop always has an offset of 3 seconds. After the loop is done it always still continues to spin for another three seconds. I already had implemented a channel override to 1500 to implement a stop once the loop is done. I do understand that channel overrides are a one-liner code and it sends an RC signal for three seconds.

I also worked on stopping RC signal by using a recursive function. It did somehow work. Here’s my sample code:

 def turnright(seconds):
     if seconds <= 3:
         vehicle.channels.overrides = {'1':1900}
         time.sleep(seconds)
         vehicle.channels.overrides = {'1':1500}
     else:
         vehicle.channels.overrides = {'1':1900}
         time.sleep(3)
         turnright(seconds - 3)

My problem is why is my channel.override={‘1’:1500} not working when using it after while loops? And how do I implement a stop movement then to avoid the three seconds offset to have accurate data?

Further details:
Rover vehicle on skid steering.
Channel 1 is the steering.
1500 is the middle RC value between 1100 and 1900.

Hi @johnmeeel,

I’m not certain of the exact cause of your issue here, but “an offset of 3 seconds” could be the amount set to the RC_OVERRIDE_TIME timeout parameter, which could happen if the last value is not being received. It may be worth adding some extra print statements / logging to your code, and/or checking your vehicle telemetry log(s) to see what controls are being sent to the vehicle and when.

You’re also comparing one code snippet which behaves based on sensor readings with another one that’s entirely timing based. It’s possible reading the sensor is taking more time than you expect, or you’re trying to read data in an endlessly blocking loop (Serial.readline blocks indefinitely if no newline character (\n) is received).

Additionally, your code has a few unusual components that may be causing problems:

  1. You’re performing “which direction do I turn” checks on the original Angle value, rather than the difference between the vehicle angle and desired angle
  2. Your code is exclusive of Angle == 180 and Angle == 0 (in which case no updates get sent)
  3. You have no explicit resting time while changing the angle, so you may be sending turn commands faster than the vehicle can meaningfully receive them
  4. You’re using the bitwise AND (&) operator instead of
    • the boolean AND (and) operator, or
    • chained comparisons (0 <= Angle < 180)

Assuming you’re using Python >= 3.8, does it work to do something like the following?

def turn_to_angle(desired_angle, measured_angle, threshold=25):
    print(f'Circle center: ({circle_centerX}, {circle_centerY}')
    while abs(error := (measured_angle - desired_angle)) > threshold:
        # TODO: check that the directions are correct
        if 0 <= error < 180 or -360 <= error < -180:
            vehicle.channels.overrides = {'1':1900} # Turn right
        else:
            vehicle.channels.overrides = {'1':1100} # Turn left
        if ser.in_waiting > 0:
            print('reading updated angle measurement... ', end='')
            measured_angle = float(ser.readline().decode('utf-8').rstrip())
            print(measured_angle)
        print(f'{time.asctime()}: {desired_angle=}, {error=}')
        time.sleep(0.1) # Wait a little while, to allow changes to happen
    print(f'Within {threshold=} - waiting one more second')
    time.sleep(1)
    vehicle.channels.overrides = {'1':1500}
    print(f'{time.asctime()}: Rotation stopped')
1 Like

Hello, Eliot! You explained it very well and your code applies my logic and it worked very well.
I have a target angle and it accesses the BNO055 sensor to know the desired angle for rotation.
Thanks a lot! It helped so much :smiley:

1 Like

I encountered the same timeout problem when running a Mission Planner Python script and found the solution in this post on DIY Drones.

I assume that MAVLink messaging is similar in Dronekit, and simply sending a PWM value of 0 will remove the override.

1 Like