Tools: port VARTest to AP_HAL

This commit is contained in:
Andrew Tridgell 2012-12-19 11:32:35 +11:00
parent 32afc3f9ae
commit cd0258c6e8
4 changed files with 72 additions and 98 deletions

View File

@ -139,18 +139,18 @@ static void load_parameters(void)
g.format_version != Parameters::k_format_version) {
// erase all parameters
Serial.printf_P(PSTR("Firmware change (%u -> %u): erasing EEPROM...\n"),
cliSerial->printf_P(PSTR("Firmware change (%u -> %u): erasing EEPROM...\n"),
g.format_version.get(), Parameters::k_format_version);
AP_Param::erase_all();
// save the current format version
g.format_version.set_and_save(Parameters::k_format_version);
Serial.println_P(PSTR("done."));
cliSerial->println_P(PSTR("done."));
} else {
unsigned long before = micros();
unsigned long before = hal.scheduler->micros();
// Load all auto-loaded EEPROM variables
AP_Param::load_all();
Serial.printf_P(PSTR("load_all took %luus\n"), micros() - before);
cliSerial->printf_P(PSTR("load_all took %luus\n"), hal.scheduler->micros() - before);
}
}

View File

@ -5,35 +5,52 @@
Andrew Tridgell February 2012
*/
#include <FastSerial.h>
#include <math.h>
#include <stdarg.h>
#include <stdio.h>
#include <AP_Common.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <PID.h> // PID library
#include <APM_RC.h> // ArduPilot Mega RC Library
#include <RC_Channel.h> // RC Channel Library
#include <AP_Progmem.h>
#include <AP_HAL.h>
#include <AP_Menu.h>
#include <AP_Param.h>
#include <AP_GPS.h> // ArduPilot GPS library
#include <AP_Baro.h> // ArduPilot barometer library
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
#include <SPI.h> // Arduino SPI lib
#include <I2C.h>
#include <AP_Semaphore.h> // for removing conflict between optical flow and dataflash on SPI3 bus
#include <DataFlash.h>
#include <AP_AHRS.h>
#include <AP_ADC.h>
#include <AP_Baro.h>
#include <Filter.h>
#include <AP_Buffer.h>
#include <GCS_MAVLink.h>
#include <AP_PeriodicProcess.h>
#include <AP_InertialSensor.h> // Inertial Sensor (uncalibated IMU) Library
#include <AP_GPS.h>
#include <AP_Math.h>
#include <SITL.h>
#include <GCS_MAVLink.h>
#include <AP_Declination.h>
#include <AP_AnalogSource.h>
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
#include <AP_ADC_AnalogSource.h>
#include <AP_InertialSensor.h> // Inertial Sensor Library
#include <AP_AHRS.h> // ArduPilot Mega DCM Library
#include <PID.h> // PID library
#include <RC_Channel.h> // RC Channel Library
#include <AP_RangeFinder.h> // Range finder library
#include <Filter.h> // Filter library
#include <AP_Buffer.h> // APM FIFO Buffer
#include <AP_Relay.h> // APM relay
#include <AP_Camera.h> // Photo or video camera
#include <AP_Airspeed.h>
#include <memcheck.h>
#include <APM_OBC.h>
#include <APM_Control.h>
#include <GCS_MAVLink.h> // MAVLink GCS definitions
#include <AP_Mount.h> // Camera/Antenna mount
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
#include <DataFlash.h>
#include <SITL.h>
#include "config.h"
#include "Parameters.h"
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_Empty.h>
AP_HAL::BetterStream* cliSerial;
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
// this sets up the parameter table, and sets the default values. This
// must be the first AP_Param variable declared to ensure its
// constructor runs before the constructors of the other AP_Param
@ -43,45 +60,36 @@ AP_Param param_loader(var_info, WP_START_BYTE);
static Parameters g;
static AP_ADC_ADS7844 adc;
static GPS *g_gps;
AP_GPS_Auto g_gps_driver(&Serial1, &g_gps);
# if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
AP_InertialSensor_MPU6000 ins( CONFIG_MPU6000_CHIP_SELECT_PIN );
# else
AP_InertialSensor_Oilpan ins( &adc );
#endif // CONFIG_IMU_TYPE
AP_GPS_Auto g_gps_driver(&g_gps);
AP_InertialSensor_MPU6000 ins;
AP_AHRS_DCM ahrs(&ins, g_gps);
Arduino_Mega_ISR_Registry isr_registry;
#ifdef DESKTOP_BUILD
AP_Compass_HIL compass;
#else
static AP_Compass_HMC5843 compass;
#endif
static AP_Compass_HIL compass;
AP_Baro_BMP085_HIL barometer;
SITL sitl;
FastSerialPort0(Serial);
FastSerialPort1(Serial1); // GPS port
#define SERIAL0_BAUD 115200
#define Debug(fmt, args...) Serial.printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__ , ##args)
#define Debug(fmt, args...) cliSerial->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__ , ##args)
void setup() {
Serial.begin(SERIAL0_BAUD, 128, 128);
cliSerial = hal.uartA;
hal.uartA->begin(SERIAL0_BAUD, 128, 128);
// load the default values of variables listed in var_info[]
AP_Param::setup_sketch_defaults();
load_parameters();
// show some sizes
Serial.printf_P(PSTR("sizeof(RC_Channel)=%u\n"), (unsigned)sizeof(RC_Channel));
Serial.printf_P(PSTR("sizeof(g)=%u\n"), (unsigned)sizeof(g));
Serial.printf_P(PSTR("sizeof(g.throttle_min)=%u\n"), (unsigned)sizeof(g.throttle_min));
Serial.printf_P(PSTR("sizeof(g.channel_roll)=%u\n"), (unsigned)sizeof(g.channel_roll));
Serial.printf_P(PSTR("throttle_max now: %u\n"), (unsigned)g.throttle_max);
cliSerial->printf_P(PSTR("sizeof(RC_Channel)=%u\n"), (unsigned)sizeof(RC_Channel));
cliSerial->printf_P(PSTR("sizeof(g)=%u\n"), (unsigned)sizeof(g));
cliSerial->printf_P(PSTR("sizeof(g.throttle_min)=%u\n"), (unsigned)sizeof(g.throttle_min));
cliSerial->printf_P(PSTR("sizeof(g.channel_roll)=%u\n"), (unsigned)sizeof(g.channel_roll));
cliSerial->printf_P(PSTR("throttle_max now: %u\n"), (unsigned)g.throttle_max);
// some ad-hoc testing
@ -90,7 +98,7 @@ void setup() {
g.throttle_min.save();
g.throttle_min.set_and_save(g.throttle_min+1);
Serial.printf_P(PSTR("throttle_min now: %u\n"), (unsigned)g.throttle_min);
cliSerial->printf_P(PSTR("throttle_min now: %u\n"), (unsigned)g.throttle_min);
// find a variable by name
AP_Param *vp;
@ -98,29 +106,29 @@ void setup() {
vp = AP_Param::find("RLL2SRV_P", &type);
((AP_Float *)vp)->set(23);
Serial.printf_P(PSTR("RLL2SRV_P=%f\n"),
cliSerial->printf_P(PSTR("RLL2SRV_P=%f\n"),
g.pidServoRoll.kP());
char s[AP_MAX_NAME_SIZE+1];
g.throttle_min.copy_name(s, sizeof(s));
s[AP_MAX_NAME_SIZE] = 0;
Serial.printf_P(PSTR("THROTTLE_MIN.copy_name()->%s\n"), s);
cliSerial->printf_P(PSTR("THROTTLE_MIN.copy_name()->%s\n"), s);
g.channel_roll.radio_min.copy_name(s, sizeof(s));
s[AP_MAX_NAME_SIZE] = 0;
Serial.printf_P(PSTR("RC1_MIN.copy_name()->%s %p\n"), s, &g.channel_roll.radio_min);
cliSerial->printf_P(PSTR("RC1_MIN.copy_name()->%s %p\n"), s, &g.channel_roll.radio_min);
Vector3f ofs;
ofs = compass.get_offsets();
Serial.printf_P(PSTR("Compass: %f %f %f\n"),
cliSerial->printf_P(PSTR("Compass: %f %f %f\n"),
ofs.x, ofs.y, ofs.z);
ofs.x += 1.1;
ofs.y += 1.2;
ofs.z += 1.3;
compass.set_offsets(ofs);
compass.save_offsets();
Serial.printf_P(PSTR("Compass: %f %f %f\n"),
cliSerial->printf_P(PSTR("Compass: %f %f %f\n"),
ofs.x, ofs.y, ofs.z);
test_vector3f();
@ -135,7 +143,7 @@ void setup() {
AP_Param::show_all();
Serial.println_P(PSTR("All done."));
cliSerial->println_P(PSTR("All done."));
}
void loop()
@ -163,13 +171,13 @@ void test_vector3f(void)
v->load();
vec = *v;
Serial.printf_P(PSTR("vec %f %f %f\n"),
cliSerial->printf_P(PSTR("vec %f %f %f\n"),
vec.x, vec.y, vec.z);
if (vec.x != 10 ||
vec.y != 11 ||
vec.z != 12) {
Serial.printf_P(PSTR("wrong value for compass vector\n"));
cliSerial->printf_P(PSTR("wrong value for compass vector\n"));
}
}
@ -183,7 +191,7 @@ void test_variable(AP_Param *ap, enum ap_var_type type)
value++;
ap->copy_name(s, sizeof(s), type==AP_PARAM_FLOAT);
Serial.printf_P(PSTR("Testing variable '%s' of type %u\n"),
cliSerial->printf_P(PSTR("Testing variable '%s' of type %u\n"),
s, type);
enum ap_var_type type2;
if (AP_Param::find(s, &type2) != ap ||
@ -364,3 +372,5 @@ void test_variable(AP_Param *ap, enum ap_var_type type)
break;
}
}
AP_HAL_MAIN();

View File

@ -46,20 +46,6 @@
// APM HARDWARE
//
#ifndef CONFIG_APM_HARDWARE
# define CONFIG_APM_HARDWARE APM_HARDWARE_APM1
#endif
#if defined( __AVR_ATmega1280__ )
#define CLI_ENABLED DISABLED
#define LOGGING_ENABLED DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// APM2 HARDWARE DEFAULTS
//
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
# define CONFIG_PUSHBUTTON DISABLED
# define CONFIG_RELAY DISABLED
@ -67,29 +53,8 @@
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
# ifdef APM2_BETA_HARDWARE
# define CONFIG_BARO AP_BARO_BMP085
# else // APM2 Production Hardware (default)
# define CONFIG_BARO AP_BARO_MS5611
# endif
#endif
# define CONFIG_BARO AP_BARO_MS5611
//////////////////////////////////////////////////////////////////////////////
// LED and IO Pins
//
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
# define A_LED_PIN 37
# define B_LED_PIN 36
# define C_LED_PIN 35
# define LED_ON HIGH
# define LED_OFF LOW
# define SLIDE_SWITCH_PIN 40
# define PUSHBUTTON_PIN 41
# define USB_MUX_PIN -1
# define CONFIG_RELAY ENABLED
# define BATTERY_PIN_1 0
# define CURRENT_PIN_1 1
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
# define A_LED_PIN 27
# define B_LED_PIN 26
# define C_LED_PIN 25
@ -101,7 +66,6 @@
# define USB_MUX_PIN 23
# define BATTERY_PIN_1 1
# define CURRENT_PIN_1 2
#endif
//////////////////////////////////////////////////////////////////////////////
// AIRSPEED_SENSOR

View File