mirror of https://github.com/ArduPilot/ardupilot
ArduPPM: cleaning
case correction for PPM_Encoder.h include from Encoder-PPM.c. Minor comment change.
This commit is contained in:
parent
70c6739fbf
commit
a9f08c9cb3
|
@ -39,7 +39,7 @@
|
||||||
// PREPROCESSOR DIRECTIVES
|
// PREPROCESSOR DIRECTIVES
|
||||||
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
|
// ------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||||
|
|
||||||
#include "..\Libraries\ppm_encoder.h"
|
#include "..\Libraries\PPM_Encoder.h"
|
||||||
#include <util/delay.h>
|
#include <util/delay.h>
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -184,7 +184,9 @@ volatile uint16_t ppm[ PPM_ARRAY_MAX ] =
|
||||||
// -------------------------------------------------------------
|
// -------------------------------------------------------------
|
||||||
// PPM OUTPUT SETTINGS
|
// PPM OUTPUT SETTINGS
|
||||||
// -------------------------------------------------------------
|
// -------------------------------------------------------------
|
||||||
// #define _POSITIVE_PPM_FRAME_ // Switch to positive PPM frame (the positive part of the signal carry the channels timing informations)
|
// #define _POSITIVE_PPM_FRAME_ // Switch to positive pulse PPM
|
||||||
|
// (the actual timing is encoded in the length of the low between two pulses)
|
||||||
|
|
||||||
|
|
||||||
// -------------------------------------------------------------
|
// -------------------------------------------------------------
|
||||||
// SERVO POWER ON VALUES
|
// SERVO POWER ON VALUES
|
||||||
|
|
Loading…
Reference in New Issue