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
This commit is contained in:
Max Basescu 2015-06-04 19:54:54 -04:00 committed by Andrew Tridgell
parent 382f5d087f
commit de50217809
1 changed files with 3 additions and 0 deletions

View File

@ -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