Browse Source

AP_HAL: Added RC_OUTPUT_MIN_PULSEWIDTH set to 400 and RC_OUTPUT_MAX_PULSEWIDTH set to 2100

For use in AP_HAL_AVR in RCOutput_APMx
master
Max Basescu 10 years ago committed by Andrew Tridgell
parent
commit
de50217809
  1. 3
      libraries/AP_HAL/RCOutput.h

3
libraries/AP_HAL/RCOutput.h

@ -4,6 +4,9 @@ @@ -4,6 +4,9 @@
#include "AP_HAL_Namespace.h"
#define RC_OUTPUT_MIN_PULSEWIDTH 400
#define RC_OUTPUT_MAX_PULSEWIDTH 2100
/* Define the CH_n names, indexed from 1, if we don't have them already */
#ifndef CH_1
#define CH_1 0

Loading…
Cancel
Save