Copter: removed HIL_MODE_ATTITUDE
this really can't work any more, as AHRS can't support it
This commit is contained in:
parent
84c7b0d7fd
commit
24f2ac20de
@ -3,9 +3,8 @@
|
|||||||
// HIL_MODE SELECTION
|
// HIL_MODE SELECTION
|
||||||
//
|
//
|
||||||
// Mavlink supports
|
// Mavlink supports
|
||||||
// 1. HIL_MODE_ATTITUDE : simulated position, airspeed, and attitude
|
// 1. HIL_MODE_SENSORS: full sensor simulation
|
||||||
// 2. HIL_MODE_SENSORS: full sensor simulation
|
#define HIL_MODE HIL_MODE_SENSORS
|
||||||
#define HIL_MODE HIL_MODE_ATTITUDE
|
|
||||||
|
|
||||||
// HIL_PORT SELCTION
|
// HIL_PORT SELCTION
|
||||||
//
|
//
|
||||||
@ -36,7 +35,4 @@
|
|||||||
|
|
||||||
// Sensors
|
// Sensors
|
||||||
// All sensors are supported in all modes.
|
// All sensors are supported in all modes.
|
||||||
// The magnetometer is not used in
|
|
||||||
// HIL_MODE_ATTITUDE but you may leave it
|
|
||||||
// enabled if you wish.
|
|
||||||
#define MAGNETOMETER ENABLED
|
#define MAGNETOMETER ENABLED
|
||||||
|
@ -318,7 +318,7 @@ AP_GPS_None g_gps_driver;
|
|||||||
|
|
||||||
static AP_AHRS_DCM ahrs(ins, g_gps);
|
static AP_AHRS_DCM ahrs(ins, g_gps);
|
||||||
|
|
||||||
#elif HIL_MODE == HIL_MODE_SENSORS
|
#elif HIL_MODE != HIL_MODE_DISABLED
|
||||||
// sensor emulators
|
// sensor emulators
|
||||||
static AP_ADC_HIL adc;
|
static AP_ADC_HIL adc;
|
||||||
static AP_Baro_HIL barometer;
|
static AP_Baro_HIL barometer;
|
||||||
@ -333,19 +333,6 @@ static AP_AHRS_DCM ahrs(ins, g_gps);
|
|||||||
static SITL sitl;
|
static SITL sitl;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#elif HIL_MODE == HIL_MODE_ATTITUDE
|
|
||||||
static AP_ADC_HIL adc;
|
|
||||||
static AP_InertialSensor_HIL ins;
|
|
||||||
static AP_AHRS_HIL ahrs(ins, g_gps);
|
|
||||||
static AP_GPS_HIL g_gps_driver;
|
|
||||||
static AP_Compass_HIL compass; // never used
|
|
||||||
static AP_Baro_HIL barometer;
|
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
|
||||||
// When building for SITL we use the HIL barometer and compass drivers
|
|
||||||
static SITL sitl;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#else
|
#else
|
||||||
#error Unrecognised HIL_MODE setting.
|
#error Unrecognised HIL_MODE setting.
|
||||||
#endif // HIL MODE
|
#endif // HIL MODE
|
||||||
@ -1067,7 +1054,6 @@ static void update_batt_compass(void)
|
|||||||
// read battery before compass because it may be used for motor interference compensation
|
// read battery before compass because it may be used for motor interference compensation
|
||||||
read_battery();
|
read_battery();
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE // don't execute in HIL mode
|
|
||||||
if(g.compass_enabled) {
|
if(g.compass_enabled) {
|
||||||
// update compass with throttle value - used for compassmot
|
// update compass with throttle value - used for compassmot
|
||||||
compass.set_throttle((float)g.rc_3.servo_out/1000.0f);
|
compass.set_throttle((float)g.rc_3.servo_out/1000.0f);
|
||||||
@ -1079,7 +1065,6 @@ static void update_batt_compass(void)
|
|||||||
Log_Write_Compass();
|
Log_Write_Compass();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
// record throttle output
|
// record throttle output
|
||||||
throttle_integrator += g.rc_3.servo_out;
|
throttle_integrator += g.rc_3.servo_out;
|
||||||
@ -1364,20 +1349,11 @@ static void read_AHRS(void)
|
|||||||
// read baro and sonar altitude at 20hz
|
// read baro and sonar altitude at 20hz
|
||||||
static void update_altitude()
|
static void update_altitude()
|
||||||
{
|
{
|
||||||
#if HIL_MODE == HIL_MODE_ATTITUDE
|
|
||||||
// we are in the SIM, fake out the baro and Sonar
|
|
||||||
baro_alt = g_gps->altitude_cm;
|
|
||||||
|
|
||||||
if(g.sonar_enabled) {
|
|
||||||
sonar_alt = baro_alt;
|
|
||||||
}
|
|
||||||
#else
|
|
||||||
// read in baro altitude
|
// read in baro altitude
|
||||||
baro_alt = read_barometer();
|
baro_alt = read_barometer();
|
||||||
|
|
||||||
// read in sonar altitude
|
// read in sonar altitude
|
||||||
sonar_alt = read_sonar();
|
sonar_alt = read_sonar();
|
||||||
#endif // HIL_MODE == HIL_MODE_ATTITUDE
|
|
||||||
|
|
||||||
// write altitude info to dataflash logs
|
// write altitude info to dataflash logs
|
||||||
if (g.log_bitmask & MASK_LOG_CTUN) {
|
if (g.log_bitmask & MASK_LOG_CTUN) {
|
||||||
@ -1518,7 +1494,6 @@ static void tuning(){
|
|||||||
g.pid_optflow_pitch.kD(tuning_value);
|
g.pid_optflow_pitch.kD(tuning_value);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE // do not allow modifying _kp or _kp_yaw gains in HIL mode
|
|
||||||
case CH6_AHRS_YAW_KP:
|
case CH6_AHRS_YAW_KP:
|
||||||
ahrs._kp_yaw.set(tuning_value);
|
ahrs._kp_yaw.set(tuning_value);
|
||||||
break;
|
break;
|
||||||
@ -1526,7 +1501,6 @@ static void tuning(){
|
|||||||
case CH6_AHRS_KP:
|
case CH6_AHRS_KP:
|
||||||
ahrs._kp.set(tuning_value);
|
ahrs._kp.set(tuning_value);
|
||||||
break;
|
break;
|
||||||
#endif
|
|
||||||
|
|
||||||
case CH6_INAV_TC:
|
case CH6_INAV_TC:
|
||||||
// To-Do: allowing tuning TC for xy and z separately
|
// To-Do: allowing tuning TC for xy and z separately
|
||||||
|
@ -1180,9 +1180,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
ahrs.set_trim(Vector3f(0,0,0)); // clear out saved trim
|
ahrs.set_trim(Vector3f(0,0,0)); // clear out saved trim
|
||||||
}
|
}
|
||||||
if (packet.param3 == 1) {
|
if (packet.param3 == 1) {
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
||||||
init_barometer(false); // fast barometer calibratoin
|
init_barometer(false); // fast barometer calibratoin
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
if (packet.param4 == 1) {
|
if (packet.param4 == 1) {
|
||||||
trim_radio();
|
trim_radio();
|
||||||
@ -1950,14 +1948,6 @@ mission_failed:
|
|||||||
barometer.setHIL(packet.alt*0.001f);
|
barometer.setHIL(packet.alt*0.001f);
|
||||||
compass.setHIL(packet.roll, packet.pitch, packet.yaw);
|
compass.setHIL(packet.roll, packet.pitch, packet.yaw);
|
||||||
|
|
||||||
#if HIL_MODE == HIL_MODE_ATTITUDE
|
|
||||||
// set AHRS hil sensor
|
|
||||||
ahrs.setHil(packet.roll,packet.pitch,packet.yaw,packet.rollspeed,
|
|
||||||
packet.pitchspeed,packet.yawspeed);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#endif // HIL_MODE != HIL_MODE_DISABLED
|
#endif // HIL_MODE != HIL_MODE_DISABLED
|
||||||
|
@ -946,9 +946,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
|
|
||||||
// @Group: INS_
|
// @Group: INS_
|
||||||
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
|
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
||||||
GOBJECT(ins, "INS_", AP_InertialSensor),
|
GOBJECT(ins, "INS_", AP_InertialSensor),
|
||||||
#endif
|
|
||||||
|
|
||||||
// @Group: INAV_
|
// @Group: INAV_
|
||||||
// @Path: ../libraries/AP_InertialNav/AP_InertialNav.cpp
|
// @Path: ../libraries/AP_InertialNav/AP_InertialNav.cpp
|
||||||
|
@ -89,8 +89,7 @@
|
|||||||
|
|
||||||
// HIL enumerations
|
// HIL enumerations
|
||||||
#define HIL_MODE_DISABLED 0
|
#define HIL_MODE_DISABLED 0
|
||||||
#define HIL_MODE_ATTITUDE 1
|
#define HIL_MODE_SENSORS 1
|
||||||
#define HIL_MODE_SENSORS 2
|
|
||||||
|
|
||||||
// Auto Pilot modes
|
// Auto Pilot modes
|
||||||
// ----------------
|
// ----------------
|
||||||
|
@ -164,10 +164,8 @@ static void init_arm_motors()
|
|||||||
startup_ground(true);
|
startup_ground(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
||||||
// fast baro calibration to reset ground pressure
|
// fast baro calibration to reset ground pressure
|
||||||
init_barometer(false);
|
init_barometer(false);
|
||||||
#endif
|
|
||||||
|
|
||||||
// go back to normal AHRS gains
|
// go back to normal AHRS gains
|
||||||
ahrs.set_fast_gains(false);
|
ahrs.set_fast_gains(false);
|
||||||
|
@ -1,8 +1,5 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
// Sensors are not available in HIL_MODE_ATTITUDE
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
||||||
|
|
||||||
#if CONFIG_SONAR == ENABLED
|
#if CONFIG_SONAR == ENABLED
|
||||||
static void init_sonar(void)
|
static void init_sonar(void)
|
||||||
{
|
{
|
||||||
@ -65,9 +62,6 @@ static int16_t read_sonar(void)
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
|
||||||
|
|
||||||
static void init_compass()
|
static void init_compass()
|
||||||
{
|
{
|
||||||
if (!compass.init() || !compass.read()) {
|
if (!compass.init() || !compass.read()) {
|
||||||
|
@ -161,9 +161,7 @@ static void init_ardupilot()
|
|||||||
|
|
||||||
rssi_analog_source = hal.analogin->channel(g.rssi_pin);
|
rssi_analog_source = hal.analogin->channel(g.rssi_pin);
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
||||||
barometer.init();
|
barometer.init();
|
||||||
#endif
|
|
||||||
|
|
||||||
// init the GCS
|
// init the GCS
|
||||||
gcs[0].init(hal.uartA);
|
gcs[0].init(hal.uartA);
|
||||||
@ -217,12 +215,10 @@ static void init_ardupilot()
|
|||||||
*/
|
*/
|
||||||
hal.scheduler->register_timer_failsafe(failsafe_check, 1000);
|
hal.scheduler->register_timer_failsafe(failsafe_check, 1000);
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
||||||
#if CONFIG_ADC == ENABLED
|
#if CONFIG_ADC == ENABLED
|
||||||
// begin filtering the ADC Gyros
|
// begin filtering the ADC Gyros
|
||||||
adc.Init(); // APM ADC library initialization
|
adc.Init(); // APM ADC library initialization
|
||||||
#endif // CONFIG_ADC
|
#endif // CONFIG_ADC
|
||||||
#endif // HIL_MODE
|
|
||||||
|
|
||||||
// Do GPS init
|
// Do GPS init
|
||||||
g_gps = &g_gps_driver;
|
g_gps = &g_gps_driver;
|
||||||
@ -268,11 +264,9 @@ static void init_ardupilot()
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
||||||
// read Baro pressure at ground
|
// read Baro pressure at ground
|
||||||
//-----------------------------
|
//-----------------------------
|
||||||
init_barometer(true);
|
init_barometer(true);
|
||||||
#endif
|
|
||||||
|
|
||||||
// initialise sonar
|
// initialise sonar
|
||||||
#if CONFIG_SONAR == ENABLED
|
#if CONFIG_SONAR == ENABLED
|
||||||
|
@ -4,7 +4,7 @@
|
|||||||
|
|
||||||
// These are function definitions so the Menu can be constructed before the functions
|
// These are function definitions so the Menu can be constructed before the functions
|
||||||
// are defined below. Order matters to the compiler.
|
// are defined below. Order matters to the compiler.
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE && HIL_MODE != HIL_MODE_SENSORS
|
#if HIL_MODE == HIL_MODE_DISABLED
|
||||||
static int8_t test_baro(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_baro(uint8_t argc, const Menu::arg *argv);
|
||||||
#endif
|
#endif
|
||||||
static int8_t test_compass(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_compass(uint8_t argc, const Menu::arg *argv);
|
||||||
@ -20,7 +20,7 @@ static int8_t test_relay(uint8_t argc, const Menu::arg *argv);
|
|||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
static int8_t test_shell(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_shell(uint8_t argc, const Menu::arg *argv);
|
||||||
#endif
|
#endif
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE && HIL_MODE != HIL_MODE_SENSORS
|
#if HIL_MODE == HIL_MODE_DISABLED
|
||||||
static int8_t test_sonar(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_sonar(uint8_t argc, const Menu::arg *argv);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -29,7 +29,7 @@ static int8_t test_sonar(uint8_t argc, const Menu::arg *argv);
|
|||||||
// User enters the string in the console to call the functions on the right.
|
// User enters the string in the console to call the functions on the right.
|
||||||
// See class Menu in AP_Coommon for implementation details
|
// See class Menu in AP_Coommon for implementation details
|
||||||
const struct Menu::command test_menu_commands[] PROGMEM = {
|
const struct Menu::command test_menu_commands[] PROGMEM = {
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE && HIL_MODE != HIL_MODE_SENSORS
|
#if HIL_MODE == HIL_MODE_DISABLED
|
||||||
{"baro", test_baro},
|
{"baro", test_baro},
|
||||||
#endif
|
#endif
|
||||||
{"compass", test_compass},
|
{"compass", test_compass},
|
||||||
@ -45,7 +45,7 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
|
|||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
{"shell", test_shell},
|
{"shell", test_shell},
|
||||||
#endif
|
#endif
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE && HIL_MODE != HIL_MODE_SENSORS
|
#if HIL_MODE == HIL_MODE_DISABLED
|
||||||
{"sonar", test_sonar},
|
{"sonar", test_sonar},
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
@ -60,7 +60,7 @@ test_mode(uint8_t argc, const Menu::arg *argv)
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE && HIL_MODE != HIL_MODE_SENSORS
|
#if HIL_MODE == HIL_MODE_DISABLED
|
||||||
static int8_t
|
static int8_t
|
||||||
test_baro(uint8_t argc, const Menu::arg *argv)
|
test_baro(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
@ -522,7 +522,7 @@ test_shell(uint8_t argc, const Menu::arg *argv)
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE && HIL_MODE != HIL_MODE_SENSORS
|
#if HIL_MODE == HIL_MODE_DISABLED
|
||||||
/*
|
/*
|
||||||
* test the sonar
|
* test the sonar
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user