How to set pwm minimum value to 0?

I’m going to use pixracer in small dc motor platform.

And I don’t use esc but simple MOSFET circuit, so I want to use pwm range from 0~1000us at 1kHz rate. (typical range is 900~2000us at 400Hz)

I know that I can’t set PWM_MIN, PWM_MAX to ranges I mentioned in “QGroundControl”
because Min, Max value of PWM_MIN, PWM_MAX doesn’t lie in this range.

However, I finally can succeed to set 0~1000us for these parameters by airframe configuration file.

Then, I succedded to run dc motor with this range by mavlink shell cmd. ex) pwm test -c 1234 -p 500

However, when I do arming in manual control, pwm value always goes to 1000 us.
Below is the information I get using pwm info command.

nsh> pwm info
device: /dev/pwm_output0
channel 1: 1000 us (alternative rate: 1000 Hz failsafe: 0, disarmed: 0 us, min: 1000 us, max: 1000 us, trim:  0.00)
channel 2: 1000 us (alternative rate: 1000 Hz failsafe: 0, disarmed: 0 us, min: 1000 us, max: 1000 us, trim:  0.00)
channel 3: 1000 us (alternative rate: 1000 Hz failsafe: 0, disarmed: 0 us, min: 1000 us, max: 1000 us, trim:  0.00)
channel 4: 1000 us (alternative rate: 1000 Hz failsafe: 0, disarmed: 0 us, min: 1000 us, max: 1000 us, trim:  0.00)
channel 5: 0 us (default rate: 50 Hz failsafe: 0, disarmed: 0 us, min: 1000 us, max: 2000 us, trim:  0.00)
channel 6: 0 us (default rate: 50 Hz failsafe: 0, disarmed: 0 us, min: 1000 us, max: 2000 us, trim:  0.00)
channel group 0: channels 1 2 3 4
channel group 1: channels 5 6

I don’t know why min value is 1000 us even if PWM_MIN = 0 us…

Maybe I have to edit source code, but I don’t know where I have to fix…
Anyone knows?

try pwm min -c 1234 -p 0

If works, you can put that your sdcard (etc/extras.txt). See

https://dev.px4.io/en/advanced/system_startup.html

1 Like

Thank you, it works substantially.

Even if I cannot set 0 for minimum value, I succeeded to set 90.

In pwm.cpp, they block if the input value is 0.
Even after I modified this block code, I cannot set 0.

Maybe it blocks at lower level in this line.

px4_ioctl(fd, PWM_SERVO_SET_MIN_PWM, (long unsigned int)&pwm_values);

Even though minimum value of 90 is enough for me,
I’m also curious what part blocks in px4_ioctl code. (it’s hard to trace lower level of this code)