mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-09 08:04:14 -03:00
test: fixed test code for HIL build
This commit is contained in:
parent
3072fdda85
commit
2a5a15abce
@ -11,9 +11,13 @@ static int8_t test_radio(uint8_t argc, const Menu::arg *argv);
|
|||||||
static int8_t test_gps(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_gps(uint8_t argc, const Menu::arg *argv);
|
||||||
//static int8_t test_tri(uint8_t argc, const Menu::arg *argv);
|
//static int8_t test_tri(uint8_t argc, const Menu::arg *argv);
|
||||||
//static int8_t test_adc(uint8_t argc, const Menu::arg *argv);
|
//static int8_t test_adc(uint8_t argc, const Menu::arg *argv);
|
||||||
|
|
||||||
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
static int8_t test_ins(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_ins(uint8_t argc, const Menu::arg *argv);
|
||||||
static int8_t test_imu(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_imu(uint8_t argc, const Menu::arg *argv);
|
||||||
static int8_t test_dcm_eulers(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_dcm_eulers(uint8_t argc, const Menu::arg *argv);
|
||||||
|
#endif // HIL_MODE
|
||||||
|
|
||||||
//static int8_t test_dcm(uint8_t argc, const Menu::arg *argv);
|
//static int8_t test_dcm(uint8_t argc, const Menu::arg *argv);
|
||||||
//static int8_t test_omega(uint8_t argc, const Menu::arg *argv);
|
//static int8_t test_omega(uint8_t argc, const Menu::arg *argv);
|
||||||
static int8_t test_battery(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_battery(uint8_t argc, const Menu::arg *argv);
|
||||||
@ -64,9 +68,11 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
|
|||||||
#if HIL_MODE != HIL_MODE_ATTITUDE && CONFIG_ADC == ENABLED
|
#if HIL_MODE != HIL_MODE_ATTITUDE && CONFIG_ADC == ENABLED
|
||||||
// {"adc", test_adc},
|
// {"adc", test_adc},
|
||||||
#endif
|
#endif
|
||||||
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
{"ins", test_ins},
|
{"ins", test_ins},
|
||||||
{"imu", test_imu},
|
{"imu", test_imu},
|
||||||
{"dcm", test_dcm_eulers},
|
{"dcm", test_dcm_eulers},
|
||||||
|
#endif
|
||||||
//{"omega", test_omega},
|
//{"omega", test_omega},
|
||||||
{"battery", test_battery},
|
{"battery", test_battery},
|
||||||
{"tune", test_tuning},
|
{"tune", test_tuning},
|
||||||
@ -423,6 +429,7 @@ static int8_t
|
|||||||
#endif
|
#endif
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
static int8_t
|
static int8_t
|
||||||
test_ins(uint8_t argc, const Menu::arg *argv)
|
test_ins(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
@ -459,8 +466,10 @@ test_ins(uint8_t argc, const Menu::arg *argv)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif // HIL_MODE
|
||||||
|
|
||||||
|
|
||||||
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
/*
|
/*
|
||||||
test the IMU interface
|
test the IMU interface
|
||||||
*/
|
*/
|
||||||
@ -495,8 +504,10 @@ test_imu(uint8_t argc, const Menu::arg *argv)
|
|||||||
}
|
}
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
#endif // HIL_MODE
|
||||||
|
|
||||||
|
|
||||||
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
/*
|
/*
|
||||||
test the DCM code, printing Euler angles
|
test the DCM code, printing Euler angles
|
||||||
*/
|
*/
|
||||||
@ -561,6 +572,7 @@ test_dcm_eulers(uint8_t argc, const Menu::arg *argv)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif // HIL_MODE
|
||||||
|
|
||||||
static int8_t
|
static int8_t
|
||||||
test_gps(uint8_t argc, const Menu::arg *argv)
|
test_gps(uint8_t argc, const Menu::arg *argv)
|
||||||
|
Loading…
Reference in New Issue
Block a user