mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
moved some defines around
This commit is contained in:
parent
c8ca841bd7
commit
da903d2c3e
@ -16,9 +16,7 @@ static int8_t setup_compass (uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_tune (uint8_t argc, const Menu::arg *argv);
|
||||
//static int8_t setup_mag_offset (uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t setup_declination (uint8_t argc, const Menu::arg *argv);
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
static int8_t setup_optflow (uint8_t argc, const Menu::arg *argv);
|
||||
#endif
|
||||
static int8_t setup_show (uint8_t argc, const Menu::arg *argv);
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
@ -43,9 +41,7 @@ const struct Menu::command setup_menu_commands[] PROGMEM = {
|
||||
{"tune", setup_tune},
|
||||
// {"offsets", setup_mag_offset},
|
||||
{"declination", setup_declination},
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
{"optflow", setup_optflow},
|
||||
#endif
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
{"heli", setup_heli},
|
||||
{"gyro", setup_gyro},
|
||||
@ -99,10 +95,7 @@ setup_show(uint8_t argc, const Menu::arg *argv)
|
||||
report_flight_modes();
|
||||
report_imu();
|
||||
report_compass();
|
||||
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
report_optflow();
|
||||
#endif
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
report_heli();
|
||||
@ -751,10 +744,10 @@ setup_mag_offset(uint8_t argc, const Menu::arg *argv)
|
||||
}
|
||||
*/
|
||||
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
static int8_t
|
||||
setup_optflow(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
if (!strcmp_P(argv[1].str, PSTR("on"))) {
|
||||
g.optflow_enabled = true;
|
||||
init_optflow();
|
||||
@ -770,9 +763,10 @@ setup_optflow(uint8_t argc, const Menu::arg *argv)
|
||||
|
||||
g.optflow_enabled.save();
|
||||
report_optflow();
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
/***************************************************************************/
|
||||
@ -897,9 +891,10 @@ static void report_flight_modes()
|
||||
print_blanks(2);
|
||||
}
|
||||
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
|
||||
void report_optflow()
|
||||
{
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
Serial.printf_P(PSTR("OptFlow\n"));
|
||||
print_divider();
|
||||
|
||||
@ -910,8 +905,9 @@ void report_optflow()
|
||||
// degrees(g.optflow_fov));
|
||||
|
||||
print_blanks(2);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
static void report_heli()
|
||||
|
Loading…
Reference in New Issue
Block a user