Multiple PWM outputs

Hello everyone,

I’m trying to control 4 brushless motors for my quadrotor using the PWMs as provided for the servo.py example by Navio. I have been able to control one motor without a problem. But when I try to use more than one, it seems the motors are switching: first one moves, it stops, then the other moves, stops, and so forth. My problem is that I would need to do this in parallel and I tried even to use multithreading but I got the same error, my code is the following:

#!/usr/bin/env python3

import rospy
import sys
import time
import threading

import navio2.pwm
import navio2.util

PWM_OUTPUT_MOTOR_1 = 0
PWM_OUTPUT_MOTOR_2 = 1
SERVO_MIN = 1.250 #ms
SERVO_MAX = 2.000 #ms

def sender1():

    #rospy.init_node('pwm_subscriber', anonymous=True)

    navio2.util.check_apm()

    with navio2.pwm.PWM(PWM_OUTPUT_MOTOR_1) as pwm1:
        time.sleep(1.0) # MEGA IMPORTANT, without a delay the code will give permission errors.
                        # Got the idea from here: https://github.com/vsergeev/python-periphery/issues/35
        pwm1.set_period(50)
        pwm1.enable()

        print("Enabling ESC")
        pwm1.set_duty_cycle(SERVO_MIN)
        time.sleep(2)
        
        while not rospy.is_shutdown():
            print("Minimums")
            pwm1.set_duty_cycle(SERVO_MIN)
            time.sleep(2)
            print("Maximum")
            pwm1.set_duty_cycle(SERVO_MAX)
            time.sleep(2)

def sender2():

    #rospy.init_node('pwm_subscriber', anonymous=True)

    navio2.util.check_apm()

    with navio2.pwm.PWM(PWM_OUTPUT_MOTOR_2) as pwm2:
        time.sleep(1.0) 
        pwm2.set_period(50)
        pwm2.enable()

        print("Enabling ESC")
        pwm2.set_duty_cycle(SERVO_MIN)
        time.sleep(2)
        
        while not rospy.is_shutdown():
            print("Minimums")
            pwm2.set_duty_cycle(SERVO_MIN)
            time.sleep(2)
            print("Maximum")
            pwm2.set_duty_cycle(SERVO_MAX)
            time.sleep(2)

if __name__ == '__main__':
    t1 = threading.Thread(target=sender1)
    t2 = threading.Thread(target=sender2)

    t1.start()
    t2.start()
 
    t1.join()
    t2.join()

I was able to solve this problem, turns out it was more a thing of my ESCs rather than a problem of my code, for me the following code worked just fine:

#!/usr/bin/env python3

import rospy
import sys
import time
import threading

import navio2.pwm
import navio2.util

PWM_OUTPUT_MOTOR_1 = 0
PWM_OUTPUT_MOTOR_2 = 1
PWM_OUTPUT_MOTOR_3 = 2
PWM_OUTPUT_MOTOR_4 = 3
SERVO_MIN = 1.250 #ms
SERVO_MAX = 2.000 #ms

def sender():

    #rospy.init_node('pwm_subscriber', anonymous=True)

    with navio2.pwm.PWM(PWM_OUTPUT_MOTOR_1) as pwm1, navio2.pwm.PWM(PWM_OUTPUT_MOTOR_2) as pwm2, navio2.pwm.PWM(PWM_OUTPUT_MOTOR_3) as pwm3, navio2.pwm.PWM(PWM_OUTPUT_MOTOR_4) as pwm4:
        time.sleep(1.0) 
        
        pwm1.set_period(400)
        pwm2.set_period(400)
        pwm3.set_period(400)
        pwm4.set_period(400)
        pwm1.enable()
        pwm2.enable()
        pwm3.enable()
        pwm4.enable()

        print("Enabling ESCs")
        pwm1.set_duty_cycle(SERVO_MIN)
        pwm2.set_duty_cycle(SERVO_MIN)
        pwm3.set_duty_cycle(SERVO_MIN)
        pwm4.set_duty_cycle(SERVO_MIN)
        time.sleep(2)
        
        while not rospy.is_shutdown():
            print("Minimums 4")
            count = 0
            while (count < 2000 and not rospy.is_shutdown()):
                pwm1.set_duty_cycle(SERVO_MAX)
                pwm2.set_duty_cycle(SERVO_MAX)
                pwm3.set_duty_cycle(SERVO_MAX)
                pwm4.set_duty_cycle(SERVO_MAX)
                count = count + 1
            count = 0
            while (count < 2000 and not rospy.is_shutdown()):
                pwm1.set_duty_cycle(SERVO_MIN+0.1)
                pwm2.set_duty_cycle(SERVO_MIN+0.3)
                pwm3.set_duty_cycle(SERVO_MIN+0.1)
                pwm4.set_duty_cycle(SERVO_MIN+0.3)
                count = count + 1

if __name__ == '__main__':
    navio2.util.check_apm()

    sender()

Hope it helps anyone looking to do the same, I would only suggest taking a look at the operational range of the ESCs (the minimum and maximum PWM). Happy coding everyone.

Gustavo,

Thank you for providing a solution!