Andrew Tridgell
10 years ago
1 changed files with 44 additions and 17 deletions
@ -1,39 +1,66 @@ |
|||||||
|
/* |
||||||
#include <AP_Common.h> |
simple test of RC output interface |
||||||
#include <AP_Math.h> |
*/ |
||||||
#include <AP_Param.h> |
|
||||||
#include <StorageManager.h> |
|
||||||
#include <AP_Progmem.h> |
|
||||||
|
|
||||||
#include <AP_HAL.h> |
#include <AP_HAL.h> |
||||||
#include <AP_HAL_AVR.h> |
#include <AP_HAL_AVR.h> |
||||||
#include <AP_HAL_AVR_SITL.h> |
#include <AP_HAL_AVR_SITL.h> |
||||||
#include <AP_HAL_PX4.h> |
#include <AP_HAL_PX4.h> |
||||||
#include <AP_HAL_Empty.h> |
#include <AP_HAL_Empty.h> |
||||||
|
#include <AP_Common.h> |
||||||
|
#include <AP_Baro.h> |
||||||
|
#include <AP_ADC.h> |
||||||
|
#include <AP_GPS.h> |
||||||
|
#include <AP_InertialSensor.h> |
||||||
|
#include <AP_Notify.h> |
||||||
|
#include <DataFlash.h> |
||||||
|
#include <GCS_MAVLink.h> |
||||||
|
#include <AP_Mission.h> |
||||||
|
#include <StorageManager.h> |
||||||
|
#include <AP_Terrain.h> |
||||||
|
#include <AP_Compass.h> |
||||||
|
#include <AP_Declination.h> |
||||||
|
#include <SITL.h> |
||||||
|
#include <Filter.h> |
||||||
|
#include <AP_Param.h> |
||||||
|
#include <AP_Progmem.h> |
||||||
|
#include <AP_Math.h> |
||||||
|
#include <AP_AHRS.h> |
||||||
|
#include <AP_Airspeed.h> |
||||||
|
#include <AP_Vehicle.h> |
||||||
|
#include <AP_ADC_AnalogSource.h> |
||||||
|
#include <AP_NavEKF.h> |
||||||
|
#include <AP_Rally.h> |
||||||
|
#include <AP_Scheduler.h> |
||||||
|
#include <UARTDriver.h> |
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; |
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; |
||||||
|
|
||||||
void setup (void) |
void setup (void) |
||||||
{ |
{ |
||||||
hal.console->printf_P(PSTR("Starting AP_HAL::RCOutput test\r\n")); |
hal.console->println("Starting AP_HAL::RCOutput test"); |
||||||
uint8_t i; |
for (uint8_t i=0; i<14; i++) { |
||||||
|
|
||||||
hal.console->printf_P(PSTR("Testing 14 channels 1050+i*50\n")); |
|
||||||
for (i=0; i<14; i++) { |
|
||||||
hal.rcout->enable_ch(i); |
hal.rcout->enable_ch(i); |
||||||
hal.rcout->write(i, 1050 + i*50); |
|
||||||
} |
} |
||||||
hal.rcout->set_freq(0xFF, 490); |
|
||||||
} |
} |
||||||
|
|
||||||
|
static uint16_t pwm = 1500; |
||||||
|
static int8_t delta = 1; |
||||||
|
|
||||||
void loop (void) |
void loop (void) |
||||||
{ |
{ |
||||||
uint8_t i; |
uint8_t i; |
||||||
for (i=0; i<14; i++) { |
for (i=0; i<14; i++) { |
||||||
hal.rcout->enable_ch(i); |
hal.rcout->write(i, pwm); |
||||||
hal.rcout->write(i, 1050 + i*50); |
pwm += delta; |
||||||
|
if (delta > 0 && pwm >= 2000) { |
||||||
|
delta = -1; |
||||||
|
hal.console->printf("reversing\n"); |
||||||
|
} else if (delta < 0 && pwm <= 1000) { |
||||||
|
delta = 1; |
||||||
|
hal.console->printf("reversing\n"); |
||||||
|
} |
||||||
} |
} |
||||||
hal.scheduler->delay(10); |
hal.scheduler->delay(5); |
||||||
} |
} |
||||||
|
|
||||||
AP_HAL_MAIN(); |
AP_HAL_MAIN(); |
||||||
|
Loading…
Reference in new issue