mirror of https://github.com/ArduPilot/ardupilot
Rover live test WORKS! "Murphy's Law is a turtle"
This commit is contained in:
parent
dac3ba48e0
commit
fd77fe5a9d
|
@ -35,8 +35,8 @@ static const uint32_t gpsBaud = 38400;
|
|||
static const uint32_t hilBaud = 115200;
|
||||
|
||||
// optional sensors
|
||||
static const bool gpsEnabled = false;
|
||||
static const bool baroEnabled = false;
|
||||
static const bool gpsEnabled = true;
|
||||
static const bool baroEnabled = true;
|
||||
static const bool compassEnabled = true;
|
||||
static const Matrix3f compassOrientation = AP_COMPASS_COMPONENTS_UP_PINS_FORWARD;
|
||||
// compass orientation: See AP_Compass_HMC5843.h for possible values
|
||||
|
|
|
@ -33,10 +33,13 @@
|
|||
|
||||
#define NUM_CHANNELS 8
|
||||
|
||||
|
||||
class Arduino_Mega_ISR_Registry;
|
||||
|
||||
class APM_RC_Class
|
||||
{
|
||||
public:
|
||||
APM_RC_Class() {}
|
||||
virtual void Init( Arduino_Mega_ISR_Registry * isr_reg );
|
||||
virtual void OutputCh(uint8_t ch, uint16_t pwm) = 0;
|
||||
virtual uint16_t InputCh(uint8_t ch) = 0;
|
||||
virtual uint8_t GetState() = 0;
|
||||
|
|
|
@ -36,11 +36,14 @@ void setup() {
|
|||
hal->debug = &Serial;
|
||||
hal->debug->println_P(PSTR("initializing debug line"));
|
||||
|
||||
// isr
|
||||
hal->isr_registry = new Arduino_Mega_ISR_Registry;
|
||||
|
||||
// initialize radio
|
||||
hal->radio = new APM_RC_APM1;
|
||||
hal->radio->Init(hal->isr_registry);
|
||||
|
||||
// initialize scheduler
|
||||
hal->isr_registry = new Arduino_Mega_ISR_Registry;
|
||||
hal->scheduler = new AP_TimerProcess;
|
||||
hal->scheduler->init(hal->isr_registry);
|
||||
|
||||
|
|
|
@ -10,6 +10,7 @@
|
|||
#include <AP_RcChannel.h> // ArduPilot Mega RC Library
|
||||
#include <APM_RC.h>
|
||||
#include <AP_Vector.h>
|
||||
#include <Arduino_Mega_ISR_Registry.h>
|
||||
FastSerialPort0(Serial)
|
||||
; // make sure this proceeds variable declarations
|
||||
|
||||
|
@ -33,38 +34,40 @@ private:
|
|||
ch8Key
|
||||
};
|
||||
Vector<AP_RcChannel *> ch;
|
||||
APM_RC_APM1 radio;
|
||||
Arduino_Mega_ISR_Registry isr_registry;
|
||||
public:
|
||||
RadioTest() :
|
||||
testPosition(2), testSign(1) {
|
||||
ch.push_back(
|
||||
new AP_RcChannel(rollKey, PSTR("ROLL"), APM_RC, 0, 1100, 1500,
|
||||
new AP_RcChannel(rollKey, PSTR("ROLL"), &radio, 0, 1100, 1500,
|
||||
1900, RC_MODE_INOUT, false));
|
||||
ch.push_back(
|
||||
new AP_RcChannel(pitchKey, PSTR("PITCH"), APM_RC, 1, 1100,
|
||||
new AP_RcChannel(pitchKey, PSTR("PITCH"), &radio, 1, 1100,
|
||||
1500, 1900, RC_MODE_INOUT, false));
|
||||
ch.push_back(
|
||||
new AP_RcChannel(thrKey, PSTR("THR"), APM_RC, 2, 1100, 1500,
|
||||
new AP_RcChannel(thrKey, PSTR("THR"), &radio, 2, 1100, 1500,
|
||||
1900, RC_MODE_INOUT, false));
|
||||
ch.push_back(
|
||||
new AP_RcChannel(yawKey, PSTR("YAW"), APM_RC, 3, 1100, 1500,
|
||||
new AP_RcChannel(yawKey, PSTR("YAW"), &radio, 3, 1100, 1500,
|
||||
1900, RC_MODE_INOUT, false));
|
||||
ch.push_back(
|
||||
new AP_RcChannel(ch5Key, PSTR("CH5"), APM_RC, 4, 1100, 1500,
|
||||
new AP_RcChannel(ch5Key, PSTR("CH5"), &radio, 4, 1100, 1500,
|
||||
1900, RC_MODE_INOUT, false));
|
||||
ch.push_back(
|
||||
new AP_RcChannel(ch6Key, PSTR("CH6"), APM_RC, 5, 1100, 1500,
|
||||
new AP_RcChannel(ch6Key, PSTR("CH6"), &radio, 5, 1100, 1500,
|
||||
1900, RC_MODE_INOUT, false));
|
||||
ch.push_back(
|
||||
new AP_RcChannel(ch7Key, PSTR("CH7"), APM_RC, 6, 1100, 1500,
|
||||
new AP_RcChannel(ch7Key, PSTR("CH7"), &radio, 6, 1100, 1500,
|
||||
1900, RC_MODE_INOUT, false));
|
||||
ch.push_back(
|
||||
new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500,
|
||||
new AP_RcChannel(ch8Key, PSTR("CH8"), &radio, 7, 1100, 1500,
|
||||
1900, RC_MODE_INOUT, false));
|
||||
|
||||
radio.Init(&isr_registry);
|
||||
|
||||
Serial.begin(57600);
|
||||
delay(2000);
|
||||
Serial.println("ArduPilot RC Channel test");
|
||||
APM_RC.Init(); // APM Radio initialization
|
||||
delay(2000);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue