mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 18:18:49 -04:00
disabled some tests with warnings
This commit is contained in:
parent
359d186798
commit
9e6ea0b167
@ -419,6 +419,10 @@ test_radio(uint8_t argc, const Menu::arg *argv)
|
|||||||
static int8_t
|
static int8_t
|
||||||
test_ins(uint8_t argc, const Menu::arg *argv)
|
test_ins(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
|
#if defined( __AVR_ATmega1280__ ) // determines if optical flow code is included
|
||||||
|
print_test_disabled();
|
||||||
|
return (0);
|
||||||
|
#else
|
||||||
float gyro[3], accel[3], temp;
|
float gyro[3], accel[3], temp;
|
||||||
print_hit_enter();
|
print_hit_enter();
|
||||||
Serial.printf_P(PSTR("InertialSensor\n"));
|
Serial.printf_P(PSTR("InertialSensor\n"));
|
||||||
@ -451,7 +455,7 @@ test_ins(uint8_t argc, const Menu::arg *argv)
|
|||||||
return (0);
|
return (0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return (0);
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -461,6 +465,10 @@ return (0);
|
|||||||
static int8_t
|
static int8_t
|
||||||
test_imu(uint8_t argc, const Menu::arg *argv)
|
test_imu(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
|
#if defined( __AVR_ATmega1280__ ) // determines if optical flow code is included
|
||||||
|
print_test_disabled();
|
||||||
|
return (0);
|
||||||
|
#else
|
||||||
Vector3f gyro;
|
Vector3f gyro;
|
||||||
Vector3f accel;
|
Vector3f accel;
|
||||||
|
|
||||||
@ -487,7 +495,7 @@ test_imu(uint8_t argc, const Menu::arg *argv)
|
|||||||
return (0);
|
return (0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return 0;
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -739,7 +747,6 @@ test_tuning(uint8_t argc, const Menu::arg *argv)
|
|||||||
static int8_t
|
static int8_t
|
||||||
test_current(uint8_t argc, const Menu::arg *argv)
|
test_current(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
|
|
||||||
print_hit_enter();
|
print_hit_enter();
|
||||||
//delta_ms_medium_loop = 100;
|
//delta_ms_medium_loop = 100;
|
||||||
|
|
||||||
@ -761,7 +768,7 @@ test_current(uint8_t argc, const Menu::arg *argv)
|
|||||||
return (0);
|
return (0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return 0;
|
return (0);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -853,7 +860,6 @@ test_wp(uint8_t argc, const Menu::arg *argv)
|
|||||||
static int8_t
|
static int8_t
|
||||||
test_baro(uint8_t argc, const Menu::arg *argv)
|
test_baro(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
|
|
||||||
print_hit_enter();
|
print_hit_enter();
|
||||||
init_barometer();
|
init_barometer();
|
||||||
|
|
||||||
@ -1007,10 +1013,13 @@ test_optflow(uint8_t argc, const Menu::arg *argv)
|
|||||||
} else {
|
} else {
|
||||||
Serial.printf_P(PSTR("OptFlow: "));
|
Serial.printf_P(PSTR("OptFlow: "));
|
||||||
print_enabled(false);
|
print_enabled(false);
|
||||||
return (0);
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
return (0);
|
return (0);
|
||||||
|
|
||||||
|
#else
|
||||||
|
print_test_disabled();
|
||||||
|
return (0);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -1080,6 +1089,11 @@ static void print_hit_enter()
|
|||||||
Serial.printf_P(PSTR("Hit Enter to exit.\n\n"));
|
Serial.printf_P(PSTR("Hit Enter to exit.\n\n"));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void print_test_disabled()
|
||||||
|
{
|
||||||
|
Serial.printf_P(PSTR("Sorry, not 1280 compat.\n"));
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
//static void fake_out_gps()
|
//static void fake_out_gps()
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user