uncrustify libraries/APM_RC/APM_RC_APM2.cpp

This commit is contained in:
uncrustify 2012-08-16 23:20:41 -07:00 committed by Pat Hickey
parent 323bc2fb1b
commit 9365bf7126

View File

@ -1,22 +1,22 @@
/* /*
APM_RC_APM2.cpp - Radio Control Library for Ardupilot Mega 2.0. Arduino * APM_RC_APM2.cpp - Radio Control Library for Ardupilot Mega 2.0. Arduino
Code by Jordi Muñoz and Jose Julio. DIYDrones.com * Code by Jordi Muñoz and Jose Julio. DIYDrones.com
*
This library is free software; you can redistribute it and/or * This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public * modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either * License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version. * version 2.1 of the License, or (at your option) any later version.
*
RC Input : PPM signal on IC4 pin * RC Input : PPM signal on IC4 pin
RC Output : 11 Servo outputs (standard 20ms frame) * RC Output : 11 Servo outputs (standard 20ms frame)
*
Methods: * Methods:
Init() : Initialization of interrupts an Timers * Init() : Initialization of interrupts an Timers
OutpuCh(ch,pwm) : Output value to servos (range : 900-2100us) ch=0..10 * OutpuCh(ch,pwm) : Output value to servos (range : 900-2100us) ch=0..10
InputCh(ch) : Read a channel input value. ch=0..7 * InputCh(ch) : Read a channel input value. ch=0..7
GetState() : Returns the state of the input. 1 => New radio frame to process * GetState() : Returns the state of the input. 1 => New radio frame to process
Automatically resets when we call InputCh to read channels * Automatically resets when we call InputCh to read channels
*
*/ */
#include "APM_RC_APM2.h" #include "APM_RC_APM2.h"
@ -36,7 +36,7 @@ volatile uint16_t APM_RC_APM2::_PWM_RAW[NUM_CHANNELS] = {2400,2400,2400,2400,240
volatile uint8_t APM_RC_APM2::_radio_status=0; volatile uint8_t APM_RC_APM2::_radio_status=0;
/**************************************************** /****************************************************
Input Capture Interrupt ICP5 => PPM signal read * Input Capture Interrupt ICP5 => PPM signal read
****************************************************/ ****************************************************/
void APM_RC_APM2::_timer5_capt_cb(void) void APM_RC_APM2::_timer5_capt_cb(void)
{ {
@ -240,10 +240,14 @@ unsigned char APM_RC_APM2::GetState(void)
// InstantPWM is not implemented! // InstantPWM is not implemented!
void APM_RC_APM2::Force_Out(void) { } void APM_RC_APM2::Force_Out(void) {
void APM_RC_APM2::Force_Out0_Out1(void) { } }
void APM_RC_APM2::Force_Out2_Out3(void) { } void APM_RC_APM2::Force_Out0_Out1(void) {
void APM_RC_APM2::Force_Out6_Out7(void) { } }
void APM_RC_APM2::Force_Out2_Out3(void) {
}
void APM_RC_APM2::Force_Out6_Out7(void) {
}
/* ---------------- OUTPUT SPEED CONTROL ------------------ */ /* ---------------- OUTPUT SPEED CONTROL ------------------ */