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 49686f18f9
commit d74e505c79

View File

@ -1,23 +1,23 @@
/*
APM_RC_APM2.cpp - Radio Control Library for Ardupilot Mega 2.0. Arduino
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
RC Input : PPM signal on IC4 pin
RC Output : 11 Servo outputs (standard 20ms frame)
Methods:
Init() : Initialization of interrupts an Timers
OutpuCh(ch,pwm) : Output value to servos (range : 900-2100us) ch=0..10
InputCh(ch) : Read a channel input value. ch=0..7
GetState() : Returns the state of the input. 1 => New radio frame to process
Automatically resets when we call InputCh to read channels
*/
* APM_RC_APM2.cpp - Radio Control Library for Ardupilot Mega 2.0. Arduino
* Code by Jordi Muñoz and Jose Julio. DIYDrones.com
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* RC Input : PPM signal on IC4 pin
* RC Output : 11 Servo outputs (standard 20ms frame)
*
* Methods:
* Init() : Initialization of interrupts an Timers
* OutpuCh(ch,pwm) : Output value to servos (range : 900-2100us) ch=0..10
* InputCh(ch) : Read a channel input value. ch=0..7
* GetState() : Returns the state of the input. 1 => New radio frame to process
* Automatically resets when we call InputCh to read channels
*
*/
#include "APM_RC_APM2.h"
#include <avr/interrupt.h>
@ -28,7 +28,7 @@
#endif
#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__)
# error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target.
# error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target.
#else
// Variable definition for Input Capture interrupt
@ -36,8 +36,8 @@ volatile uint16_t APM_RC_APM2::_PWM_RAW[NUM_CHANNELS] = {2400,2400,2400,2400,240
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)
{
static uint16_t prev_icr;
@ -164,7 +164,7 @@ void APM_RC_APM2::OutputCh(unsigned char ch, uint16_t pwm)
uint16_t APM_RC_APM2::OutputCh_current(uint8_t ch)
{
uint16_t pwm=0;
switch(ch){
switch(ch) {
case 0: pwm=OCR1B; break; // out1
case 1: pwm=OCR1A; break; // out2
case 2: pwm=OCR4C; break; // out3
@ -240,10 +240,14 @@ unsigned char APM_RC_APM2::GetState(void)
// InstantPWM is not implemented!
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_Out6_Out7(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_Out6_Out7(void) {
}
/* ---------------- OUTPUT SPEED CONTROL ------------------ */