mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
reduce test.pde size for 1280 users
This commit is contained in:
parent
0213f4dd88
commit
9dd1730cce
@ -94,7 +94,7 @@ test_mode(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
//Serial.printf_P(PSTR("Test Mode\n\n"));
|
||||
test_menu.run();
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int8_t
|
||||
@ -469,7 +469,7 @@ test_ins(uint8_t argc, const Menu::arg *argv)
|
||||
static int8_t
|
||||
test_imu(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
#if defined( __AVR_ATmega1280__ ) // determines if optical flow code is included
|
||||
#if defined( __AVR_ATmega1280__ ) // determines if optical flow code is included
|
||||
print_test_disabled();
|
||||
return (0);
|
||||
#else
|
||||
@ -515,7 +515,7 @@ test_imu(uint8_t argc, const Menu::arg *argv)
|
||||
//dcm.kp_yaw(0.02);
|
||||
//dcm.ki_yaw(0);
|
||||
|
||||
imu.init(IMU::WARM_START, delay, flash_leds, &timer_scheduler);
|
||||
imu.init(IMU::WARM_START, delay, flash_leds, &timer_scheduler);
|
||||
|
||||
report_imu();
|
||||
imu.init_gyro(delay, flash_leds);
|
||||
@ -555,7 +555,7 @@ test_imu(uint8_t argc, const Menu::arg *argv)
|
||||
compass.calculate(dcm.get_dcm_matrix());
|
||||
}
|
||||
}
|
||||
fast_loopTimer = millis();
|
||||
fast_loopTimer = millis();
|
||||
}
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
@ -731,59 +731,68 @@ test_tuning(uint8_t argc, const Menu::arg *argv)
|
||||
static int8_t
|
||||
test_battery(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
//delta_ms_medium_loop = 100;
|
||||
#if defined( __AVR_ATmega1280__ ) // determines if optical flow code is included
|
||||
print_test_disabled();
|
||||
return (0);
|
||||
#else
|
||||
print_hit_enter();
|
||||
while(1){
|
||||
delay(100);
|
||||
read_radio();
|
||||
read_battery();
|
||||
if (g.battery_monitoring == 3){
|
||||
Serial.printf_P(PSTR("V: %4.4f\n"),
|
||||
battery_voltage1,
|
||||
current_amps1,
|
||||
current_total1);
|
||||
} else {
|
||||
Serial.printf_P(PSTR("V: %4.4f, A: %4.4f, Ah: %4.4f\n"),
|
||||
battery_voltage1,
|
||||
current_amps1,
|
||||
current_total1);
|
||||
}
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_in);
|
||||
|
||||
while(1){
|
||||
delay(100);
|
||||
read_radio();
|
||||
read_battery();
|
||||
if (g.battery_monitoring == 3){
|
||||
Serial.printf_P(PSTR("V: %4.4f\n"),
|
||||
battery_voltage1,
|
||||
current_amps1,
|
||||
current_total1);
|
||||
} else {
|
||||
Serial.printf_P(PSTR("V: %4.4f, A: %4.4f, Ah: %4.4f\n"),
|
||||
battery_voltage1,
|
||||
current_amps1,
|
||||
current_total1);
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_in);
|
||||
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
return (0);
|
||||
return (0);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
static int8_t test_relay(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
#if defined( __AVR_ATmega1280__ ) // determines if optical flow code is included
|
||||
print_test_disabled();
|
||||
return (0);
|
||||
#else
|
||||
|
||||
while(1){
|
||||
Serial.printf_P(PSTR("Relay on\n"));
|
||||
relay.on();
|
||||
delay(3000);
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
|
||||
Serial.printf_P(PSTR("Relay off\n"));
|
||||
relay.off();
|
||||
delay(3000);
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
while(1){
|
||||
Serial.printf_P(PSTR("Relay on\n"));
|
||||
relay.on();
|
||||
delay(3000);
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
|
||||
Serial.printf_P(PSTR("Relay off\n"));
|
||||
relay.off();
|
||||
delay(3000);
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
static int8_t
|
||||
test_wp(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
@ -810,20 +819,20 @@ test_wp(uint8_t argc, const Menu::arg *argv)
|
||||
/*
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
while(1){
|
||||
if (Serial3.available()){
|
||||
digitalWrite(B_LED_PIN, LED_ON); // Blink Yellow LED if we are sending data to GPS
|
||||
Serial1.write(Serial3.read());
|
||||
digitalWrite(B_LED_PIN, LED_OFF);
|
||||
}
|
||||
if (Serial1.available()){
|
||||
digitalWrite(C_LED_PIN, LED_ON); // Blink Red LED if we are receiving data from GPS
|
||||
Serial3.write(Serial1.read());
|
||||
digitalWrite(C_LED_PIN, LED_OFF);
|
||||
}
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
while(1){
|
||||
if (Serial3.available()){
|
||||
digitalWrite(B_LED_PIN, LED_ON); // Blink Yellow LED if we are sending data to GPS
|
||||
Serial1.write(Serial3.read());
|
||||
digitalWrite(B_LED_PIN, LED_OFF);
|
||||
}
|
||||
if (Serial1.available()){
|
||||
digitalWrite(C_LED_PIN, LED_ON); // Blink Red LED if we are receiving data from GPS
|
||||
Serial3.write(Serial1.read());
|
||||
digitalWrite(C_LED_PIN, LED_OFF);
|
||||
}
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
*/
|
||||
//}
|
||||
@ -836,7 +845,7 @@ test_wp(uint8_t argc, const Menu::arg *argv)
|
||||
Serial.printf_P(PSTR("Begin XBee X-CTU Range and RSSI Test:\n"));
|
||||
|
||||
while(1){
|
||||
if (Serial3.available())
|
||||
if (Serial3.available())
|
||||
Serial3.write(Serial3.read());
|
||||
|
||||
if(Serial.available() > 0){
|
||||
@ -850,30 +859,30 @@ test_wp(uint8_t argc, const Menu::arg *argv)
|
||||
static int8_t
|
||||
test_baro(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
init_barometer();
|
||||
#if defined( __AVR_ATmega1280__ ) // determines if optical flow code is included
|
||||
print_test_disabled();
|
||||
return (0);
|
||||
#else
|
||||
print_hit_enter();
|
||||
init_barometer();
|
||||
|
||||
while(1){
|
||||
delay(100);
|
||||
int32_t alt = read_barometer(); // calls barometer.read()
|
||||
while(1){
|
||||
delay(100);
|
||||
int32_t alt = read_barometer(); // calls barometer.read()
|
||||
|
||||
#if defined( __AVR_ATmega1280__ )
|
||||
Serial.printf_P(PSTR("alt: %ldcm\n"),alt);
|
||||
|
||||
#else
|
||||
int32_t pres = barometer.get_pressure();
|
||||
int16_t temp = barometer.get_temperature();
|
||||
int32_t raw_pres = barometer.get_raw_pressure();
|
||||
int32_t raw_temp = barometer.get_raw_temp();
|
||||
Serial.printf_P(PSTR("alt: %ldcm, pres: %ldmbar, temp: %d/100degC,"
|
||||
" raw pres: %ld, raw temp: %ld\n"),
|
||||
alt, pres ,temp, raw_pres, raw_temp);
|
||||
#endif
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
int32_t pres = barometer.get_pressure();
|
||||
int16_t temp = barometer.get_temperature();
|
||||
int32_t raw_pres = barometer.get_raw_pressure();
|
||||
int32_t raw_temp = barometer.get_raw_temp();
|
||||
Serial.printf_P(PSTR("alt: %ldcm, pres: %ldmbar, temp: %d/100degC,"
|
||||
" raw pres: %ld, raw temp: %ld\n"),
|
||||
alt, pres ,temp, raw_pres, raw_temp);
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -881,35 +890,38 @@ test_baro(uint8_t argc, const Menu::arg *argv)
|
||||
static int8_t
|
||||
test_mag(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
if(g.compass_enabled) {
|
||||
//Serial.printf_P(PSTR("MAG_ORIENTATION: %d\n"), MAG_ORIENTATION);
|
||||
|
||||
print_hit_enter();
|
||||
|
||||
while(1){
|
||||
delay(100);
|
||||
if (compass.read()) {
|
||||
compass.calculate(dcm.get_dcm_matrix());
|
||||
Vector3f maggy = compass.get_offsets();
|
||||
Serial.printf_P(PSTR("Heading: %ld, XYZ: %d, %d, %d\n"),
|
||||
(wrap_360(ToDeg(compass.heading) * 100)) /100,
|
||||
compass.mag_x,
|
||||
compass.mag_y,
|
||||
compass.mag_z);
|
||||
} else {
|
||||
Serial.println_P(PSTR("not healthy"));
|
||||
}
|
||||
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
Serial.printf_P(PSTR("Compass: "));
|
||||
print_enabled(false);
|
||||
#if defined( __AVR_ATmega1280__ ) // determines if optical flow code is included
|
||||
print_test_disabled();
|
||||
return (0);
|
||||
}
|
||||
return (0);
|
||||
#else
|
||||
if(g.compass_enabled) {
|
||||
print_hit_enter();
|
||||
|
||||
while(1){
|
||||
delay(100);
|
||||
if (compass.read()) {
|
||||
compass.calculate(dcm.get_dcm_matrix());
|
||||
Vector3f maggy = compass.get_offsets();
|
||||
Serial.printf_P(PSTR("Heading: %ld, XYZ: %d, %d, %d\n"),
|
||||
(wrap_360(ToDeg(compass.heading) * 100)) /100,
|
||||
compass.mag_x,
|
||||
compass.mag_y,
|
||||
compass.mag_z);
|
||||
} else {
|
||||
Serial.println_P(PSTR("not healthy"));
|
||||
}
|
||||
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
Serial.printf_P(PSTR("Compass: "));
|
||||
print_enabled(false);
|
||||
return (0);
|
||||
}
|
||||
return (0);
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
@ -1023,25 +1035,31 @@ test_optflow(uint8_t argc, const Menu::arg *argv)
|
||||
/*
|
||||
test the dataflash is working
|
||||
*/
|
||||
|
||||
static int8_t
|
||||
test_logging(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
Serial.println_P(PSTR("Testing dataflash logging"));
|
||||
if (!DataFlash.CardInserted()) {
|
||||
Serial.println_P(PSTR("ERR: No dataflash inserted"));
|
||||
return 0;
|
||||
}
|
||||
DataFlash.ReadManufacturerID();
|
||||
Serial.printf_P(PSTR("Manufacturer: 0x%02x Device: 0x%04x\n"),
|
||||
(unsigned)DataFlash.df_manufacturer,
|
||||
(unsigned)DataFlash.df_device);
|
||||
Serial.printf_P(PSTR("NumPages: %u PageSize: %u\n"),
|
||||
(unsigned)DataFlash.df_NumPages+1,
|
||||
(unsigned)DataFlash.df_PageSize);
|
||||
DataFlash.StartRead(DataFlash.df_NumPages+1);
|
||||
Serial.printf_P(PSTR("Format version: %lx Expected format version: %lx\n"),
|
||||
(unsigned long)DataFlash.ReadLong(), (unsigned long)DF_LOGGING_FORMAT);
|
||||
return 0;
|
||||
#if defined( __AVR_ATmega1280__ ) // determines if optical flow code is included
|
||||
print_test_disabled();
|
||||
return (0);
|
||||
#else
|
||||
Serial.println_P(PSTR("Testing dataflash logging"));
|
||||
if (!DataFlash.CardInserted()) {
|
||||
Serial.println_P(PSTR("ERR: No dataflash inserted"));
|
||||
return 0;
|
||||
}
|
||||
DataFlash.ReadManufacturerID();
|
||||
Serial.printf_P(PSTR("Manufacturer: 0x%02x Device: 0x%04x\n"),
|
||||
(unsigned)DataFlash.df_manufacturer,
|
||||
(unsigned)DataFlash.df_device);
|
||||
Serial.printf_P(PSTR("NumPages: %u PageSize: %u\n"),
|
||||
(unsigned)DataFlash.df_NumPages+1,
|
||||
(unsigned)DataFlash.df_PageSize);
|
||||
DataFlash.StartRead(DataFlash.df_NumPages+1);
|
||||
Serial.printf_P(PSTR("Format version: %lx Expected format version: %lx\n"),
|
||||
(unsigned long)DataFlash.ReadLong(), (unsigned long)DF_LOGGING_FORMAT);
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@ -1061,11 +1079,11 @@ static int8_t
|
||||
//}
|
||||
|
||||
// clear home
|
||||
{Location t = {0, 0, 0, 0, 0, 0};
|
||||
{Location t = {0, 0, 0, 0, 0, 0};
|
||||
set_cmd_with_index(t,0);}
|
||||
|
||||
// CMD opt pitch alt/cm
|
||||
{Location t = {MAV_CMD_NAV_TAKEOFF, WP_OPTION_RELATIVE, 0, 100, 0, 0};
|
||||
{Location t = {MAV_CMD_NAV_TAKEOFF, WP_OPTION_RELATIVE, 0, 100, 0, 0};
|
||||
set_cmd_with_index(t,1);}
|
||||
|
||||
if (!strcmp_P(argv[1].str, PSTR("wp"))) {
|
||||
@ -1074,25 +1092,25 @@ static int8_t
|
||||
{Location t = {MAV_CMD_NAV_WAYPOINT, WP_OPTION_RELATIVE, 15, 0, 0, 0};
|
||||
set_cmd_with_index(t,2);}
|
||||
// CMD opt
|
||||
{Location t = {MAV_CMD_NAV_RETURN_TO_LAUNCH, WP_OPTION_YAW, 0, 0, 0, 0};
|
||||
{Location t = {MAV_CMD_NAV_RETURN_TO_LAUNCH, WP_OPTION_YAW, 0, 0, 0, 0};
|
||||
set_cmd_with_index(t,3);}
|
||||
|
||||
// CMD opt
|
||||
{Location t = {MAV_CMD_NAV_LAND, 0, 0, 0, 0, 0};
|
||||
{Location t = {MAV_CMD_NAV_LAND, 0, 0, 0, 0, 0};
|
||||
set_cmd_with_index(t,4);}
|
||||
|
||||
} else {
|
||||
//2250 = 25 meteres
|
||||
// CMD opt p1 //alt //NS //WE
|
||||
{Location t = {MAV_CMD_NAV_LOITER_TIME, 0, 10, 0, 0, 0}; // 19
|
||||
{Location t = {MAV_CMD_NAV_LOITER_TIME, 0, 10, 0, 0, 0}; // 19
|
||||
set_cmd_with_index(t,2);}
|
||||
|
||||
// CMD opt dir angle/deg deg/s relative
|
||||
{Location t = {MAV_CMD_CONDITION_YAW, 0, 1, 360, 60, 1};
|
||||
{Location t = {MAV_CMD_CONDITION_YAW, 0, 1, 360, 60, 1};
|
||||
set_cmd_with_index(t,3);}
|
||||
|
||||
// CMD opt
|
||||
{Location t = {MAV_CMD_NAV_LAND, 0, 0, 0, 0, 0};
|
||||
{Location t = {MAV_CMD_NAV_LAND, 0, 0, 0, 0, 0};
|
||||
set_cmd_with_index(t,4);}
|
||||
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user