mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
ArduPlane: move to use new INS library instead of IMU library
This commit is contained in:
parent
68bdf93a4d
commit
ef727bbb3c
@ -449,13 +449,13 @@
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// GROUND_START_DELAY OPTIONAL
|
||||
//
|
||||
// If configured, inserts a delay between power-up and the beginning of IMU
|
||||
// If configured, inserts a delay between power-up and the beginning of INS
|
||||
// calibration during a ground start.
|
||||
//
|
||||
// Use this setting to give you time to position the aircraft horizontally
|
||||
// for the IMU calibration.
|
||||
// for the INS calibration.
|
||||
//
|
||||
// The default is to begin IMU calibration immediately at startup.
|
||||
// The default is to begin INS calibration immediately at startup.
|
||||
//
|
||||
//#define GROUND_START_DELAY 0
|
||||
//
|
||||
@ -463,7 +463,7 @@
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ENABLE_AIR_START OPTIONAL
|
||||
//
|
||||
// If air start is disabled then you will get a ground start (including IMU
|
||||
// If air start is disabled then you will get a ground start (including INS
|
||||
// calibration) every time the AP is powered up. This means that if you get
|
||||
// a power glitch or reboot for some reason in the air, you will probably
|
||||
// crash, but it prevents a lot of problems on the ground like unintentional
|
||||
@ -863,7 +863,7 @@
|
||||
//
|
||||
// LOG_PM OPTIONAL
|
||||
//
|
||||
// Logs IMU performance monitoring info every 20 seconds.
|
||||
// Logs INS performance monitoring info every 20 seconds.
|
||||
// Defaults to DISABLED.
|
||||
//
|
||||
// LOG_CTUN OPTIONAL
|
||||
|
@ -41,13 +41,13 @@
|
||||
#include <AP_Baro.h> // ArduPilot barometer library
|
||||
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <AP_InertialSensor.h> // Inertial Sensor (uncalibrated IMU) Library
|
||||
#include <AP_IMU.h> // ArduPilot Mega IMU Library
|
||||
#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 <ModeFilter.h> // Mode Filter from Filter library
|
||||
#include <LowPassFilter.h> // LowPassFilter class (inherits from Filter class)
|
||||
#include <AP_Relay.h> // APM relay
|
||||
@ -215,14 +215,13 @@ AP_GPS_None g_gps_driver(NULL);
|
||||
#error Unrecognised GPS_PROTOCOL setting.
|
||||
#endif // GPS PROTOCOL
|
||||
|
||||
# if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
|
||||
# if CONFIG_INS_TYPE == CONFIG_INS_MPU6000
|
||||
AP_InertialSensor_MPU6000 ins;
|
||||
# else
|
||||
AP_InertialSensor_Oilpan ins( &adc );
|
||||
#endif // CONFIG_IMU_TYPE
|
||||
AP_IMU_INS imu( &ins );
|
||||
#endif // CONFIG_INS_TYPE
|
||||
|
||||
AP_AHRS_DCM ahrs(&imu, g_gps);
|
||||
AP_AHRS_DCM ahrs(&ins, g_gps);
|
||||
|
||||
#elif HIL_MODE == HIL_MODE_SENSORS
|
||||
// sensor emulators
|
||||
@ -231,13 +230,11 @@ AP_Baro_BMP085_HIL barometer;
|
||||
AP_Compass_HIL compass;
|
||||
AP_GPS_HIL g_gps_driver(NULL);
|
||||
AP_InertialSensor_Oilpan ins( &adc );
|
||||
AP_IMU_Shim imu;
|
||||
AP_AHRS_DCM ahrs(&imu, g_gps);
|
||||
AP_AHRS_DCM ahrs(&ins, g_gps);
|
||||
|
||||
#elif HIL_MODE == HIL_MODE_ATTITUDE
|
||||
AP_ADC_HIL adc;
|
||||
AP_IMU_Shim imu; // never used
|
||||
AP_AHRS_HIL ahrs(&imu, g_gps);
|
||||
AP_AHRS_HIL ahrs(&ins, g_gps);
|
||||
AP_GPS_HIL g_gps_driver(NULL);
|
||||
AP_Compass_HIL compass; // never used
|
||||
AP_Baro_BMP085_HIL barometer;
|
||||
@ -480,7 +477,7 @@ AP_Airspeed airspeed(&pitot_analog_source);
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// flight mode specific
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Flag for using gps ground course instead of IMU yaw. Set false when takeoff command in process.
|
||||
// Flag for using gps ground course instead of INS yaw. Set false when takeoff command in process.
|
||||
static bool takeoff_complete = true;
|
||||
// Flag to indicate if we have landed.
|
||||
//Set land_complete if we are within 2 seconds distance or within 3 meters altitude of touchdown
|
||||
@ -605,7 +602,7 @@ static int32_t target_altitude_cm;
|
||||
static int32_t offset_altitude_cm;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// IMU variables
|
||||
// INS variables
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// The main loop execution time. Seconds
|
||||
//This is the time between calls to the DCM algorithm and is the Integration time for the gyros.
|
||||
@ -689,8 +686,8 @@ void setup() {
|
||||
void loop()
|
||||
{
|
||||
// We want this to execute at 50Hz, but synchronised with the gyro/accel
|
||||
uint16_t num_samples = imu.num_samples_available();
|
||||
if (num_samples >= NUM_IMU_SAMPLES_FOR_50HZ) {
|
||||
uint16_t num_samples = ins.num_samples_available();
|
||||
if (num_samples >= NUM_INS_SAMPLES_FOR_50HZ) {
|
||||
delta_ms_fast_loop = millis() - fast_loopTimer_ms;
|
||||
load = (float)(fast_loopTimeStamp_ms - fast_loopTimer_ms)/delta_ms_fast_loop;
|
||||
G_Dt = (float)delta_ms_fast_loop / 1000.f;
|
||||
@ -724,7 +721,7 @@ void loop()
|
||||
}
|
||||
|
||||
fast_loopTimeStamp_ms = millis();
|
||||
} else if (num_samples < NUM_IMU_SAMPLES_FOR_50HZ-1) {
|
||||
} else if (num_samples < NUM_INS_SAMPLES_FOR_50HZ-1) {
|
||||
// less than 20ms has passed. We have at least one millisecond
|
||||
// of free time. The most useful thing to do with that time is
|
||||
// to accumulate some sensor readings, specifically the
|
||||
@ -835,7 +832,7 @@ static void medium_loop()
|
||||
* Serial.print(ahrs.roll_sensor, DEC); Serial.printf_P(PSTR("\t"));
|
||||
* Serial.print(ahrs.pitch_sensor, DEC); Serial.printf_P(PSTR("\t"));
|
||||
* Serial.print(ahrs.yaw_sensor, DEC); Serial.printf_P(PSTR("\t"));
|
||||
* Vector3f tempaccel = imu.get_accel();
|
||||
* Vector3f tempaccel = ins.get_accel();
|
||||
* Serial.print(tempaccel.x, DEC); Serial.printf_P(PSTR("\t"));
|
||||
* Serial.print(tempaccel.y, DEC); Serial.printf_P(PSTR("\t"));
|
||||
* Serial.println(tempaccel.z, DEC);
|
||||
|
@ -207,7 +207,7 @@ static void calc_nav_yaw(float speed_scaler, float ch4_inf)
|
||||
g.channel_rudder.servo_out = g.kff_rudder_mix * g.channel_roll.servo_out;
|
||||
|
||||
// a PID to coordinate the turn (drive y axis accel to zero)
|
||||
Vector3f temp = imu.get_accel();
|
||||
Vector3f temp = ins.get_accel();
|
||||
int32_t error = -temp.y*100.0;
|
||||
|
||||
g.channel_rudder.servo_out += g.pidServoRudder.get_pid(error, speed_scaler);
|
||||
|
@ -353,8 +353,8 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
static void NOINLINE send_raw_imu1(mavlink_channel_t chan)
|
||||
{
|
||||
Vector3f accel = imu.get_accel();
|
||||
Vector3f gyro = imu.get_gyro();
|
||||
Vector3f accel = ins.get_accel();
|
||||
Vector3f gyro = ins.get_gyro();
|
||||
|
||||
mavlink_msg_raw_imu_send(
|
||||
chan,
|
||||
@ -392,8 +392,8 @@ static void NOINLINE send_raw_imu3(mavlink_channel_t chan)
|
||||
compass.get_declination(),
|
||||
barometer.get_raw_pressure(),
|
||||
barometer.get_raw_temp(),
|
||||
imu.gx(), imu.gy(), imu.gz(),
|
||||
imu.ax(), imu.ay(), imu.az());
|
||||
ins.gx(), ins.gy(), ins.gz(),
|
||||
ins.ax(), ins.ay(), ins.az());
|
||||
}
|
||||
|
||||
static void NOINLINE send_ahrs(mavlink_channel_t chan)
|
||||
@ -1034,7 +1034,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
case MAV_CMD_PREFLIGHT_CALIBRATION:
|
||||
if (packet.param1 == 1 ||
|
||||
packet.param2 == 1) {
|
||||
startup_IMU_ground(true);
|
||||
startup_INS_ground(true);
|
||||
} else if (packet.param3 == 1) {
|
||||
init_barometer();
|
||||
if (airspeed.enabled()) {
|
||||
@ -1796,9 +1796,9 @@ mission_failed:
|
||||
accels.y = (float)packet.yacc / 1000.0;
|
||||
accels.z = (float)packet.zacc / 1000.0;
|
||||
|
||||
imu.set_gyro(gyros);
|
||||
ins.set_gyro_offsets(gyros);
|
||||
|
||||
imu.set_accel(accels);
|
||||
ins.set_accel_offsets(accels);
|
||||
|
||||
#else
|
||||
|
||||
@ -1850,9 +1850,9 @@ mission_failed:
|
||||
accels.y = (float)packet.yacc / 1000.0;
|
||||
accels.z = (float)packet.zacc / 1000.0;
|
||||
|
||||
imu.set_gyro(gyros);
|
||||
ins.set_gyro_offsets(gyros);
|
||||
|
||||
imu.set_accel(accels);
|
||||
ins.set_accel_offsets(accels);
|
||||
|
||||
compass.setHIL(packet.xmag,packet.ymag,packet.zmag);
|
||||
break;
|
||||
|
@ -232,7 +232,7 @@ static void Log_Write_Performance()
|
||||
DataFlash.WriteInt((int16_t)mainLoop_count);
|
||||
DataFlash.WriteInt(G_Dt_max);
|
||||
DataFlash.WriteByte(0);
|
||||
DataFlash.WriteByte(imu.adc_constraints);
|
||||
DataFlash.WriteByte(0);
|
||||
DataFlash.WriteByte(ahrs.renorm_range_count);
|
||||
DataFlash.WriteByte(ahrs.renorm_blowup_count);
|
||||
DataFlash.WriteByte(gps_fix_count);
|
||||
@ -285,7 +285,7 @@ static void Log_Write_Startup(byte type)
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
static void Log_Write_Control_Tuning()
|
||||
{
|
||||
Vector3f accel = imu.get_accel();
|
||||
Vector3f accel = ins.get_accel();
|
||||
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
@ -353,8 +353,8 @@ static void Log_Write_GPS( int32_t log_Time, int32_t log_Lattitude, int32_t
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
static void Log_Write_Raw()
|
||||
{
|
||||
Vector3f gyro = imu.get_gyro();
|
||||
Vector3f accel = imu.get_accel();
|
||||
Vector3f gyro = ins.get_gyro();
|
||||
Vector3f accel = ins.get_accel();
|
||||
gyro *= t7; // Scale up for storage as long integers
|
||||
accel *= t7;
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
|
@ -633,16 +633,12 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GOBJECT(gcs0, "SR0_", GCS_MAVLINK),
|
||||
GOBJECT(gcs3, "SR3_", GCS_MAVLINK),
|
||||
|
||||
#if HIL_MODE == HIL_MODE_DISABLED && CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
||||
#if HIL_MODE == HIL_MODE_DISABLED
|
||||
// @Group: INS_
|
||||
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp
|
||||
GOBJECT(ins, "INS_", AP_InertialSensor_Oilpan),
|
||||
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
|
||||
GOBJECT(ins, "INS_", AP_InertialSensor),
|
||||
#endif
|
||||
|
||||
// @Group: IMU_
|
||||
// @Path: ../libraries/AP_IMU/IMU.cpp
|
||||
GOBJECT(imu, "IMU_", IMU),
|
||||
|
||||
// @Group: AHRS_
|
||||
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
|
||||
GOBJECT(ahrs, "AHRS_", AP_AHRS),
|
||||
|
@ -87,7 +87,7 @@
|
||||
//
|
||||
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
|
||||
# define CONFIG_INS_TYPE CONFIG_INS_MPU6000
|
||||
# define CONFIG_RELAY DISABLED
|
||||
# define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD
|
||||
# define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN
|
||||
@ -135,17 +135,17 @@
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// IMU Selection
|
||||
// INS Selection
|
||||
//
|
||||
#ifndef CONFIG_IMU_TYPE
|
||||
# define CONFIG_IMU_TYPE CONFIG_IMU_OILPAN
|
||||
#ifndef CONFIG_INS_TYPE
|
||||
# define CONFIG_INS_TYPE CONFIG_INS_OILPAN
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ADC Enable - used to eliminate for systems which don't have ADC.
|
||||
//
|
||||
#ifndef CONFIG_ADC
|
||||
# if CONFIG_IMU_TYPE == CONFIG_IMU_OILPAN
|
||||
# if CONFIG_INS_TYPE == CONFIG_INS_OILPAN
|
||||
# define CONFIG_ADC ENABLED
|
||||
# else
|
||||
# define CONFIG_ADC DISABLED
|
||||
@ -823,14 +823,14 @@
|
||||
# define SERIAL_BUFSIZE 256
|
||||
#endif
|
||||
|
||||
#if CONFIG_IMU_TYPE == CONFIG_IMU_OILPAN
|
||||
# define NUM_IMU_SAMPLES_FOR_200HZ 5
|
||||
# define NUM_IMU_SAMPLES_FOR_100HZ 10
|
||||
# define NUM_IMU_SAMPLES_FOR_50HZ 20
|
||||
#if CONFIG_INS_TYPE == CONFIG_INS_OILPAN
|
||||
# define NUM_INS_SAMPLES_FOR_200HZ 5
|
||||
# define NUM_INS_SAMPLES_FOR_100HZ 10
|
||||
# define NUM_INS_SAMPLES_FOR_50HZ 20
|
||||
#endif
|
||||
|
||||
#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
|
||||
# define NUM_IMU_SAMPLES_FOR_200HZ 1
|
||||
# define NUM_IMU_SAMPLES_FOR_100HZ 2
|
||||
# define NUM_IMU_SAMPLES_FOR_50HZ 4
|
||||
#if CONFIG_INS_TYPE == CONFIG_INS_MPU6000
|
||||
# define NUM_INS_SAMPLES_FOR_200HZ 1
|
||||
# define NUM_INS_SAMPLES_FOR_100HZ 2
|
||||
# define NUM_INS_SAMPLES_FOR_50HZ 4
|
||||
#endif
|
||||
|
@ -241,8 +241,8 @@ enum gcs_severity {
|
||||
// mark a function as not to be inlined
|
||||
#define NOINLINE __attribute__((noinline))
|
||||
|
||||
#define CONFIG_IMU_OILPAN 1
|
||||
#define CONFIG_IMU_MPU6000 2
|
||||
#define CONFIG_INS_OILPAN 1
|
||||
#define CONFIG_INS_MPU6000 2
|
||||
|
||||
#define APM_HARDWARE_APM1 1
|
||||
#define APM_HARDWARE_APM2 2
|
||||
|
@ -193,7 +193,7 @@ endforeach()
|
||||
#set(THROTTLE_OUT "ENABLED" CACHE STRING "Disabled throttle output? (useful for debugging)?")
|
||||
#set_property(CACHE THROTTLE_OUT PROPERTY STRINGS ENABLED DISABLED)
|
||||
|
||||
#set(GROUND_START_DELAY "0" CACHE STRING "Delay between power-up and IMU calibration (s)?")
|
||||
#set(GROUND_START_DELAY "0" CACHE STRING "Delay between power-up and INS calibration (s)?")
|
||||
|
||||
#set(ENABLE_AIR_START "DISABLED" CACHE STRING "Enable in-air restart?")
|
||||
#set_property(CACHE ENABLE_AIR_START PROPERTY STRINGS ENABLED DISABLED)
|
||||
|
@ -8,6 +8,7 @@ static int8_t setup_show (uint8_t argc, const Men
|
||||
static int8_t setup_factory (uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_flightmodes (uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_level (uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_accel_scale (uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_erase (uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_compass (uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_declination (uint8_t argc, const Menu::arg *argv);
|
||||
@ -21,6 +22,7 @@ static const struct Menu::command setup_menu_commands[] PROGMEM = {
|
||||
{"radio", setup_radio},
|
||||
{"modes", setup_flightmodes},
|
||||
{"level", setup_level},
|
||||
{"accel", setup_accel_scale},
|
||||
{"compass", setup_compass},
|
||||
{"declination", setup_declination},
|
||||
{"battery", setup_batt_monitor},
|
||||
@ -62,7 +64,7 @@ setup_show(uint8_t argc, const Menu::arg *argv)
|
||||
report_xtrack();
|
||||
report_throttle();
|
||||
report_flight_modes();
|
||||
report_imu();
|
||||
report_ins();
|
||||
report_compass();
|
||||
|
||||
Serial.printf_P(PSTR("Raw Values\n"));
|
||||
@ -293,10 +295,19 @@ setup_erase(uint8_t argc, const Menu::arg *argv)
|
||||
static int8_t
|
||||
setup_level(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
startup_IMU_ground(true);
|
||||
startup_INS_ground(true);
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int8_t
|
||||
setup_accel_scale(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
ins.init(AP_InertialSensor::COLD_START, delay, flash_leds, &timer_scheduler);
|
||||
ins.calibrate_accel(delay, flash_leds);
|
||||
report_ins();
|
||||
return(0);
|
||||
}
|
||||
|
||||
static int8_t
|
||||
setup_compass(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
@ -427,14 +438,14 @@ static void report_throttle()
|
||||
print_blanks(2);
|
||||
}
|
||||
|
||||
static void report_imu()
|
||||
static void report_ins()
|
||||
{
|
||||
//print_blanks(2);
|
||||
Serial.printf_P(PSTR("IMU\n"));
|
||||
Serial.printf_P(PSTR("INS\n"));
|
||||
print_divider();
|
||||
|
||||
print_gyro_offsets();
|
||||
print_accel_offsets();
|
||||
print_accel_offsets_and_scaling();
|
||||
print_blanks(2);
|
||||
}
|
||||
|
||||
@ -594,21 +605,27 @@ static void print_enabled(bool b)
|
||||
}
|
||||
|
||||
static void
|
||||
print_accel_offsets(void)
|
||||
print_accel_offsets_and_scaling(void)
|
||||
{
|
||||
Serial.printf_P(PSTR("Accel offsets: %4.2f, %4.2f, %4.2f\n"),
|
||||
(float)imu.ax(),
|
||||
(float)imu.ay(),
|
||||
(float)imu.az());
|
||||
Vector3f accel_offsets = ins.get_accel_offsets();
|
||||
Vector3f accel_scale = ins.get_accel_scale();
|
||||
Serial.printf_P(PSTR("Accel offsets: %4.2f, %4.2f, %4.2f\tscale: %4.2f, %4.2f, %4.2f\n"),
|
||||
(float)accel_offsets.x, // Pitch
|
||||
(float)accel_offsets.y, // Roll
|
||||
(float)accel_offsets.z, // YAW
|
||||
(float)accel_scale.x, // Pitch
|
||||
(float)accel_scale.y, // Roll
|
||||
(float)accel_scale.z); // YAW
|
||||
}
|
||||
|
||||
static void
|
||||
print_gyro_offsets(void)
|
||||
{
|
||||
Vector3f gyro_offsets = ins.get_gyro_offsets();
|
||||
Serial.printf_P(PSTR("Gyro offsets: %4.2f, %4.2f, %4.2f\n"),
|
||||
(float)imu.gx(),
|
||||
(float)imu.gy(),
|
||||
(float)imu.gz());
|
||||
(float)gyro_offsets.x,
|
||||
(float)gyro_offsets.y,
|
||||
(float)gyro_offsets.z);
|
||||
}
|
||||
|
||||
|
||||
|
@ -232,9 +232,8 @@ static void init_ardupilot()
|
||||
//----------------
|
||||
//read_EEPROM_airstart_critical();
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
imu.init(IMU::WARM_START, mavlink_delay, flash_leds, &timer_scheduler);
|
||||
ins.init(AP_InertialSensor::WARM_START, mavlink_delay, flash_leds, &timer_scheduler);
|
||||
|
||||
// initialise ahrs (may push imu calibration into the mpu6000 if using that device).
|
||||
ahrs.init(&timer_scheduler);
|
||||
ahrs.set_fly_forward(true);
|
||||
#endif
|
||||
@ -286,10 +285,10 @@ static void startup_ground(void)
|
||||
// -----------------------
|
||||
demo_servos(1);
|
||||
|
||||
//IMU ground start
|
||||
//INS ground start
|
||||
//------------------------
|
||||
//
|
||||
startup_IMU_ground(false);
|
||||
startup_INS_ground(false);
|
||||
|
||||
// read the radio to set trims
|
||||
// ---------------------------
|
||||
@ -411,23 +410,23 @@ static void check_short_failsafe()
|
||||
}
|
||||
|
||||
|
||||
static void startup_IMU_ground(bool force_accel_level)
|
||||
static void startup_INS_ground(bool force_accel_level)
|
||||
{
|
||||
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Warming up ADC..."));
|
||||
mavlink_delay(500);
|
||||
|
||||
// Makes the servos wiggle twice - about to begin IMU calibration - HOLD LEVEL AND STILL!!
|
||||
// Makes the servos wiggle twice - about to begin INS calibration - HOLD LEVEL AND STILL!!
|
||||
// -----------------------
|
||||
demo_servos(2);
|
||||
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Beginning IMU calibration; do not move plane"));
|
||||
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Beginning INS calibration; do not move plane"));
|
||||
mavlink_delay(1000);
|
||||
|
||||
imu.init(IMU::COLD_START, mavlink_delay, flash_leds, &timer_scheduler);
|
||||
ins.init(AP_InertialSensor::COLD_START, mavlink_delay, flash_leds, &timer_scheduler);
|
||||
if (force_accel_level || g.manual_level == 0) {
|
||||
// when MANUAL_LEVEL is set to 1 we don't do accelerometer
|
||||
// levelling on each boot, and instead rely on the user to do
|
||||
// it once via the ground station
|
||||
imu.init_accel(mavlink_delay, flash_leds);
|
||||
ins.init_accel(mavlink_delay, flash_leds);
|
||||
}
|
||||
ahrs.set_fly_forward(true);
|
||||
ahrs.reset();
|
||||
@ -446,7 +445,7 @@ static void startup_IMU_ground(bool force_accel_level)
|
||||
}
|
||||
|
||||
#endif
|
||||
digitalWrite(B_LED_PIN, LED_ON); // Set LED B high to indicate IMU ready
|
||||
digitalWrite(B_LED_PIN, LED_ON); // Set LED B high to indicate INS ready
|
||||
digitalWrite(A_LED_PIN, LED_OFF);
|
||||
digitalWrite(C_LED_PIN, LED_OFF);
|
||||
}
|
||||
@ -483,7 +482,6 @@ static void update_GPS_light(void)
|
||||
static void resetPerfData(void) {
|
||||
mainLoop_count = 0;
|
||||
G_Dt_max = 0;
|
||||
imu.adc_constraints = 0;
|
||||
ahrs.renorm_range_count = 0;
|
||||
ahrs.renorm_blowup_count = 0;
|
||||
gps_fix_count = 0;
|
||||
|
@ -12,7 +12,7 @@ static int8_t test_gps(uint8_t argc, const Menu::arg *argv);
|
||||
#if CONFIG_ADC == ENABLED
|
||||
static int8_t test_adc(uint8_t argc, const Menu::arg *argv);
|
||||
#endif
|
||||
static int8_t test_imu(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_ins(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_battery(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_relay(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_wp(uint8_t argc, const Menu::arg *argv);
|
||||
@ -49,14 +49,14 @@ static const struct Menu::command test_menu_commands[] PROGMEM = {
|
||||
#endif
|
||||
{"gps", test_gps},
|
||||
{"rawgps", test_rawgps},
|
||||
{"imu", test_imu},
|
||||
{"ins", test_ins},
|
||||
{"airspeed", test_airspeed},
|
||||
{"airpressure", test_pressure},
|
||||
{"compass", test_mag},
|
||||
#elif HIL_MODE == HIL_MODE_SENSORS
|
||||
{"adc", test_adc},
|
||||
{"gps", test_gps},
|
||||
{"imu", test_imu},
|
||||
{"ins", test_ins},
|
||||
{"compass", test_mag},
|
||||
#elif HIL_MODE == HIL_MODE_ATTITUDE
|
||||
#endif
|
||||
@ -464,10 +464,10 @@ test_gps(uint8_t argc, const Menu::arg *argv)
|
||||
}
|
||||
|
||||
static int8_t
|
||||
test_imu(uint8_t argc, const Menu::arg *argv)
|
||||
test_ins(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
//Serial.printf_P(PSTR("Calibrating."));
|
||||
imu.init(IMU::COLD_START, delay, flash_leds, &timer_scheduler);
|
||||
ins.init(AP_InertialSensor::COLD_START, delay, flash_leds, &timer_scheduler);
|
||||
ahrs.reset();
|
||||
|
||||
print_hit_enter();
|
||||
@ -480,7 +480,7 @@ test_imu(uint8_t argc, const Menu::arg *argv)
|
||||
G_Dt = (float)delta_ms_fast_loop / 1000.f; // used by DCM integrator
|
||||
fast_loopTimer_ms = millis();
|
||||
|
||||
// IMU
|
||||
// INS
|
||||
// ---
|
||||
ahrs.update();
|
||||
|
||||
@ -492,10 +492,10 @@ test_imu(uint8_t argc, const Menu::arg *argv)
|
||||
}
|
||||
}
|
||||
|
||||
// We are using the IMU
|
||||
// We are using the INS
|
||||
// ---------------------
|
||||
Vector3f gyros = imu.get_gyro();
|
||||
Vector3f accels = imu.get_accel();
|
||||
Vector3f gyros = ins.get_gyro();
|
||||
Vector3f accels = ins.get_accel();
|
||||
Serial.printf_P(PSTR("r:%4d p:%4d y:%3d g=(%5.1f %5.1f %5.1f) a=(%5.1f %5.1f %5.1f)\n"),
|
||||
(int)ahrs.roll_sensor / 100,
|
||||
(int)ahrs.pitch_sensor / 100,
|
||||
@ -528,7 +528,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
|
||||
report_compass();
|
||||
|
||||
// we need the AHRS initialised for this test
|
||||
imu.init(IMU::COLD_START, delay, flash_leds, &timer_scheduler);
|
||||
ins.init(AP_InertialSensor::COLD_START, delay, flash_leds, &timer_scheduler);
|
||||
ahrs.reset();
|
||||
|
||||
int16_t counter = 0;
|
||||
@ -545,7 +545,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
|
||||
G_Dt = (float)delta_ms_fast_loop / 1000.f; // used by DCM integrator
|
||||
fast_loopTimer_ms = millis();
|
||||
|
||||
// IMU
|
||||
// INS
|
||||
// ---
|
||||
ahrs.update();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user