Browse Source

AP_HAL_FLYMAPLE: remove checks for HAL_BOARD_APM2 and HAL_BOARD_APM1

mission-4.1.18
Lucas De Marchi 9 years ago committed by Andrew Tridgell
parent
commit
973c3c6bc6
  1. 1
      libraries/AP_HAL_FLYMAPLE/AnalogSource.cpp
  2. 2
      libraries/AP_HAL_FLYMAPLE/HAL_FLYMAPLE_Class.cpp
  3. 5
      libraries/AP_HAL_FLYMAPLE/examples/Console/Console.cpp
  4. 9
      libraries/AP_HAL_FLYMAPLE/examples/Scheduler/Scheduler.cpp
  5. 15
      libraries/AP_HAL_FLYMAPLE/examples/Semaphore/Semaphore.cpp
  6. 4
      libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/UARTDriver.cpp

1
libraries/AP_HAL_FLYMAPLE/AnalogSource.cpp

@ -170,7 +170,6 @@ bool FLYMAPLEAnalogSource::reading_settled() @@ -170,7 +170,6 @@ bool FLYMAPLEAnalogSource::reading_settled()
void FLYMAPLEAnalogSource::new_sample(uint16_t sample) {
_sum += sample;
_latest = sample;
// Copied from AVR code in ArduPlane-2.74b, but AVR code is wrong!
if (_sum_count >= 15) { // Flymaple has a 12 bit ADC, so can only sum 16 in a uint16_t
_sum >>= 1;
_sum_count = 8;

2
libraries/AP_HAL_FLYMAPLE/HAL_FLYMAPLE_Class.cpp

@ -79,8 +79,6 @@ void HAL_FLYMAPLE::run(int argc, char* const argv[], Callbacks* callbacks) const @@ -79,8 +79,6 @@ void HAL_FLYMAPLE::run(int argc, char* const argv[], Callbacks* callbacks) const
* it is initialized at boot */
uartA->begin(115200);
/* The AVR RCInput drivers take an AP_HAL_AVR::ISRRegistry*
* as the init argument */
rcin->init(NULL);
rcout->init(NULL);
spi->init(NULL);

5
libraries/AP_HAL_FLYMAPLE/examples/Console/Console.cpp

@ -1,10 +1,5 @@ @@ -1,10 +1,5 @@
// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*-
//
// Example code for the AP_HAL AVRUARTDriver, based on FastSerial
//
// This code is placed into the public domain.
//
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>

9
libraries/AP_HAL_FLYMAPLE/examples/Scheduler/Scheduler.cpp

@ -8,11 +8,12 @@ @@ -8,11 +8,12 @@
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
/**
/*
* You'll want to use a logic analyzer to watch the effects of this test.
* On the APM2 its pretty easy to hook up an analyzer to pins A0 through A3.
* Define each of the pins below to the pins used during the test on your
* board.
*/
#define DELAY_TOGGLE_PIN 15 /* A0 = pin 15 */
#define DELAY_TOGGLE_PIN 15 /* A0 = pin 15 */
#define FAILSAFE_TOGGLE_PIN 16 /* A1 = pin 16 */
#define SCHEDULED_TOGGLE_PIN_1 17 /* A2 = pin 17 */
#define SCHEDULED_TOGGLE_PIN_2 18 /* A3 = pin 18 */
@ -61,7 +62,7 @@ void setup_pin(int pin_num) { @@ -61,7 +62,7 @@ void setup_pin(int pin_num) {
void setup (void) {
// hal.scheduler->delay(5000);
hal.console->printf("Starting AP_HAL_AVR::Scheduler test\r\n");
hal.console->printf("Starting AP_HAL::Scheduler test\r\n");
setup_pin(DELAY_TOGGLE_PIN);
setup_pin(FAILSAFE_TOGGLE_PIN);

15
libraries/AP_HAL_FLYMAPLE/examples/Semaphore/Semaphore.cpp

@ -7,17 +7,18 @@ @@ -7,17 +7,18 @@
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
/**
/*
* You'll want to use a logic analyzer to watch the effects of this test.
* On the APM2 its pretty easy to hook up an analyzer to pins A0 through A3.
* Define each of the pins below to the pins used during the test on your
* board.
*/
#define PIN_A0 15 /* A0 */
#define PIN_A1 16 /* A1 */
#define PIN_A2 17 /* A2 */
#define PIN_A3 18 /* A3 */
#define PIN_A0 15
#define PIN_A1 16
#define PIN_A2 17
#define PIN_A3 18
/**
* Create an AVRSemaphore for this test.
* Create a Semaphore for this test.
*/
AP_HAL::Semaphore *sem;

4
libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/UARTDriver.cpp

@ -1,10 +1,6 @@ @@ -1,10 +1,6 @@
// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*-
//
// Example code for the AP_HAL AVRUARTDriver, based on FastSerial
//
// This code is placed into the public domain.
//
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>

Loading…
Cancel
Save