|
|
|
@ -61,7 +61,7 @@ static int8_t
@@ -61,7 +61,7 @@ static int8_t
|
|
|
|
|
setup_mode(uint8_t argc, const Menu::arg *argv) |
|
|
|
|
{ |
|
|
|
|
// Give the user some guidance |
|
|
|
|
Serial.printf_P(PSTR("Setup Mode\n\n\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Setup Mode\n\n\n")); |
|
|
|
|
//"\n" |
|
|
|
|
//"IMPORTANT: if you have not previously set this system up, use the\n" |
|
|
|
|
//"'reset' command to initialize the EEPROM to sensible default values\n" |
|
|
|
@ -70,9 +70,9 @@ setup_mode(uint8_t argc, const Menu::arg *argv)
@@ -70,9 +70,9 @@ setup_mode(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
|
|
|
|
|
if(g.rc_1.radio_min >= 1300) { |
|
|
|
|
delay(1000); |
|
|
|
|
Serial.printf_P(PSTR("\n!Warning, radio not configured!")); |
|
|
|
|
cliSerial->printf_P(PSTR("\n!Warning, radio not configured!")); |
|
|
|
|
delay(1000); |
|
|
|
|
Serial.printf_P(PSTR("\n Type 'radio' now.\n\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\n Type 'radio' now.\n\n")); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// Run the setup menu. When the menu exits, we will return to the main menu. |
|
|
|
@ -118,17 +118,17 @@ setup_factory(uint8_t argc, const Menu::arg *argv)
@@ -118,17 +118,17 @@ setup_factory(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
{ |
|
|
|
|
int16_t c; |
|
|
|
|
|
|
|
|
|
Serial.printf_P(PSTR("\n'Y' = factory reset, any other key to abort:\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\n'Y' = factory reset, any other key to abort:\n")); |
|
|
|
|
|
|
|
|
|
do { |
|
|
|
|
c = Serial.read(); |
|
|
|
|
c = cliSerial->read(); |
|
|
|
|
} while (-1 == c); |
|
|
|
|
|
|
|
|
|
if (('y' != c) && ('Y' != c)) |
|
|
|
|
return(-1); |
|
|
|
|
|
|
|
|
|
AP_Param::erase_all(); |
|
|
|
|
Serial.printf_P(PSTR("\nReboot APM")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nReboot APM")); |
|
|
|
|
|
|
|
|
|
delay(1000); |
|
|
|
|
//default_gains(); |
|
|
|
@ -144,7 +144,7 @@ setup_factory(uint8_t argc, const Menu::arg *argv)
@@ -144,7 +144,7 @@ setup_factory(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
static int8_t |
|
|
|
|
setup_radio(uint8_t argc, const Menu::arg *argv) |
|
|
|
|
{ |
|
|
|
|
Serial.println_P(PSTR("\n\nRadio Setup:")); |
|
|
|
|
cliSerial->println_P(PSTR("\n\nRadio Setup:")); |
|
|
|
|
uint8_t i; |
|
|
|
|
|
|
|
|
|
for(i = 0; i < 100; i++) { |
|
|
|
@ -154,7 +154,7 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
@@ -154,7 +154,7 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
|
|
|
|
|
if(g.rc_1.radio_in < 500) { |
|
|
|
|
while(1) { |
|
|
|
|
//Serial.printf_P(PSTR("\nNo radio; Check connectors.")); |
|
|
|
|
//cliSerial->printf_P(PSTR("\nNo radio; Check connectors.")); |
|
|
|
|
delay(1000); |
|
|
|
|
// stop here |
|
|
|
|
} |
|
|
|
@ -188,7 +188,7 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
@@ -188,7 +188,7 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
g.rc_8.radio_trim = 1500; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
Serial.printf_P(PSTR("\nMove all controls to extremes. Enter to save: ")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nMove all controls to extremes. Enter to save: ")); |
|
|
|
|
while(1) { |
|
|
|
|
|
|
|
|
|
delay(20); |
|
|
|
@ -205,9 +205,9 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
@@ -205,9 +205,9 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
g.rc_7.update_min_max(); |
|
|
|
|
g.rc_8.update_min_max(); |
|
|
|
|
|
|
|
|
|
if(Serial.available() > 0) { |
|
|
|
|
if(cliSerial->available() > 0) { |
|
|
|
|
delay(20); |
|
|
|
|
Serial.flush(); |
|
|
|
|
cliSerial->flush(); |
|
|
|
|
|
|
|
|
|
g.rc_1.save_eeprom(); |
|
|
|
|
g.rc_2.save_eeprom(); |
|
|
|
@ -229,7 +229,7 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
@@ -229,7 +229,7 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
static int8_t |
|
|
|
|
setup_motors(uint8_t argc, const Menu::arg *argv) |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR( |
|
|
|
|
cliSerial->printf_P(PSTR( |
|
|
|
|
"Now connect the main lipo and follow the instruction on the wiki for your frame setup.\n" |
|
|
|
|
"For security remember to disconnect the main lipo after the test, then hit any key to exit.\n" |
|
|
|
|
"Any key to exit.\n")); |
|
|
|
@ -237,7 +237,7 @@ setup_motors(uint8_t argc, const Menu::arg *argv)
@@ -237,7 +237,7 @@ setup_motors(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
delay(20); |
|
|
|
|
read_radio(); |
|
|
|
|
motors.output_test(); |
|
|
|
|
if(Serial.available() > 0) { |
|
|
|
|
if(cliSerial->available() > 0) { |
|
|
|
|
g.esc_calibrate.set_and_save(0); |
|
|
|
|
return(0); |
|
|
|
|
} |
|
|
|
@ -253,12 +253,37 @@ setup_accel(uint8_t argc, const Menu::arg *argv)
@@ -253,12 +253,37 @@ setup_accel(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
return(0); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* |
|
|
|
|
handle full accelerometer calibration via user dialog |
|
|
|
|
*/ |
|
|
|
|
|
|
|
|
|
static void setup_printf_P(const prog_char_t *fmt, ...) |
|
|
|
|
{ |
|
|
|
|
va_list arg_list; |
|
|
|
|
va_start(arg_list, fmt); |
|
|
|
|
cliSerial->vprintf_P(fmt, arg_list); |
|
|
|
|
va_end(arg_list); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
static void setup_wait_key(void) |
|
|
|
|
{ |
|
|
|
|
// wait for user input |
|
|
|
|
while (!cliSerial->available()) { |
|
|
|
|
delay(20); |
|
|
|
|
} |
|
|
|
|
// clear input buffer |
|
|
|
|
while( cliSerial->available() ) { |
|
|
|
|
cliSerial->read(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
static int8_t |
|
|
|
|
setup_accel_scale(uint8_t argc, const Menu::arg *argv) |
|
|
|
|
{ |
|
|
|
|
cliSerial->println_P(PSTR("Initialising gyros")); |
|
|
|
|
ins.init(AP_InertialSensor::COLD_START, delay, flash_leds, &timer_scheduler); |
|
|
|
|
ins.calibrate_accel(delay, flash_leds, gcs_send_text_fmt); |
|
|
|
|
ins.calibrate_accel(delay, flash_leds, setup_printf_P, setup_wait_key); |
|
|
|
|
report_ins(); |
|
|
|
|
return(0); |
|
|
|
|
} |
|
|
|
@ -275,7 +300,7 @@ setup_frame(uint8_t argc, const Menu::arg *argv)
@@ -275,7 +300,7 @@ setup_frame(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
} else if (!strcmp_P(argv[1].str, PSTR("v"))) { |
|
|
|
|
g.frame_orientation.set_and_save(V_FRAME); |
|
|
|
|
}else{ |
|
|
|
|
Serial.printf_P(PSTR("\nOp:[x,+,v]\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nOp:[x,+,v]\n")); |
|
|
|
|
report_frame(); |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
@ -291,7 +316,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
@@ -291,7 +316,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
byte _oldSwitchPosition = 0; |
|
|
|
|
int8_t mode = 0; |
|
|
|
|
|
|
|
|
|
Serial.printf_P(PSTR("\nMode switch to edit, aileron: select modes, rudder: Simple on/off\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nMode switch to edit, aileron: select modes, rudder: Simple on/off\n")); |
|
|
|
|
print_hit_enter(); |
|
|
|
|
|
|
|
|
|
while(1) { |
|
|
|
@ -344,7 +369,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
@@ -344,7 +369,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// escape hatch |
|
|
|
|
if(Serial.available() > 0) { |
|
|
|
|
if(cliSerial->available() > 0) { |
|
|
|
|
for (mode = 0; mode < 6; mode++) |
|
|
|
|
flight_modes[mode].save(); |
|
|
|
|
|
|
|
|
@ -377,7 +402,7 @@ setup_tune(uint8_t argc, const Menu::arg *argv)
@@ -377,7 +402,7 @@ setup_tune(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
static int8_t |
|
|
|
|
setup_range(uint8_t argc, const Menu::arg *argv) |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("\nCH 6 Ranges are divided by 1000: [low, high]\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nCH 6 Ranges are divided by 1000: [low, high]\n")); |
|
|
|
|
|
|
|
|
|
g.radio_tuning_low.set_and_save(argv[1].i); |
|
|
|
|
g.radio_tuning_high.set_and_save(argv[2].i); |
|
|
|
@ -406,7 +431,7 @@ setup_compass(uint8_t argc, const Menu::arg *argv)
@@ -406,7 +431,7 @@ setup_compass(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
g.compass_enabled.set_and_save(false); |
|
|
|
|
|
|
|
|
|
}else{ |
|
|
|
|
Serial.printf_P(PSTR("\nOp:[on,off]\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nOp:[on,off]\n")); |
|
|
|
|
report_compass(); |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
@ -426,7 +451,7 @@ setup_batt_monitor(uint8_t argc, const Menu::arg *argv)
@@ -426,7 +451,7 @@ setup_batt_monitor(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
g.battery_monitoring.set_and_save(argv[1].i); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
Serial.printf_P(PSTR("\nOp: off, 3-4")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nOp: off, 3-4")); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
report_batt_monitor(); |
|
|
|
@ -447,7 +472,7 @@ setup_sonar(uint8_t argc, const Menu::arg *argv)
@@ -447,7 +472,7 @@ setup_sonar(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
g.sonar_type.set_and_save(argv[1].i); |
|
|
|
|
|
|
|
|
|
}else{ |
|
|
|
|
Serial.printf_P(PSTR("\nOp:[on, off, 0-3]\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nOp:[on, off, 0-3]\n")); |
|
|
|
|
report_sonar(); |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
@ -480,18 +505,18 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
@@ -480,18 +505,18 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
report_heli(); |
|
|
|
|
|
|
|
|
|
// display help |
|
|
|
|
Serial.printf_P(PSTR("Instructions:")); |
|
|
|
|
cliSerial->printf_P(PSTR("Instructions:")); |
|
|
|
|
print_divider(); |
|
|
|
|
Serial.printf_P(PSTR("\td\t\tdisplay settings\n")); |
|
|
|
|
Serial.printf_P(PSTR("\t1~4\t\tselect servo\n")); |
|
|
|
|
Serial.printf_P(PSTR("\ta or z\t\tmove mid up/down\n")); |
|
|
|
|
Serial.printf_P(PSTR("\tc\t\tset coll when blade pitch zero\n")); |
|
|
|
|
Serial.printf_P(PSTR("\tm\t\tset roll, pitch, coll min/max\n")); |
|
|
|
|
Serial.printf_P(PSTR("\tp<angle>\tset pos (i.e. p0 = front, p90 = right)\n")); |
|
|
|
|
Serial.printf_P(PSTR("\tr\t\treverse servo\n")); |
|
|
|
|
Serial.printf_P(PSTR("\tu a|d\t\tupdate rate (a=analog servo, d=digital)\n")); |
|
|
|
|
Serial.printf_P(PSTR("\tt<angle>\tset trim (-500 ~ 500)\n")); |
|
|
|
|
Serial.printf_P(PSTR("\tx\t\texit & save\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\td\t\tdisplay settings\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\t1~4\t\tselect servo\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\ta or z\t\tmove mid up/down\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\tc\t\tset coll when blade pitch zero\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\tm\t\tset roll, pitch, coll min/max\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\tp<angle>\tset pos (i.e. p0 = front, p90 = right)\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\tr\t\treverse servo\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\tu a|d\t\tupdate rate (a=analog servo, d=digital)\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\tt<angle>\tset trim (-500 ~ 500)\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\tx\t\texit & save\n")); |
|
|
|
|
|
|
|
|
|
// start capturing |
|
|
|
|
while( value != 'x' ) { |
|
|
|
@ -516,8 +541,8 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
@@ -516,8 +541,8 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
max_tail = max(g.rc_4.radio_out, max_tail); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if( Serial.available() ) { |
|
|
|
|
value = Serial.read(); |
|
|
|
|
if( cliSerial->available() ) { |
|
|
|
|
value = cliSerial->read(); |
|
|
|
|
|
|
|
|
|
// process the user's input |
|
|
|
|
switch( value ) { |
|
|
|
@ -541,7 +566,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
@@ -541,7 +566,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
case 'C': |
|
|
|
|
if( g.rc_3.radio_out >= 900 && g.rc_3.radio_out <= 2100 ) { |
|
|
|
|
motors.collective_mid = g.rc_3.radio_out; |
|
|
|
|
Serial.printf_P(PSTR("Collective when blade pitch at zero: %d\n"),(int)motors.collective_mid); |
|
|
|
|
cliSerial->printf_P(PSTR("Collective when blade pitch at zero: %d\n"),(int)motors.collective_mid); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case 'd': |
|
|
|
@ -553,7 +578,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
@@ -553,7 +578,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
case 'M': |
|
|
|
|
if( state == 0 ) { |
|
|
|
|
state = 1; // switch to capture min/max mode |
|
|
|
|
Serial.printf_P(PSTR("Move coll, roll, pitch and tail to extremes, press 'm' when done\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Move coll, roll, pitch and tail to extremes, press 'm' when done\n")); |
|
|
|
|
|
|
|
|
|
// reset servo ranges |
|
|
|
|
motors.roll_max = motors.pitch_max = 4500; |
|
|
|
@ -572,7 +597,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
@@ -572,7 +597,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
state = 0; // switch back to normal mode |
|
|
|
|
// double check values aren't totally terrible |
|
|
|
|
if( max_roll <= 1000 || max_pitch <= 1000 || (max_collective - min_collective < 200) || (max_tail - min_tail < 200) || min_tail < 1000 || max_tail > 2000 ) |
|
|
|
|
Serial.printf_P(PSTR("Invalid min/max captured roll:%d, pitch:%d, collective min: %d max: %d, tail min:%d max:%d\n"),max_roll,max_pitch,min_collective,max_collective,min_tail,max_tail); |
|
|
|
|
cliSerial->printf_P(PSTR("Invalid min/max captured roll:%d, pitch:%d, collective min: %d max: %d, tail min:%d max:%d\n"),max_roll,max_pitch,min_collective,max_collective,min_tail,max_tail); |
|
|
|
|
else{ |
|
|
|
|
motors.roll_max = max_roll; |
|
|
|
|
motors.pitch_max = max_pitch; |
|
|
|
@ -600,7 +625,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
@@ -600,7 +625,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
if( active_servo == CH_3 ) |
|
|
|
|
motors.servo3_pos = temp; |
|
|
|
|
motors.init_swash(); |
|
|
|
|
Serial.printf_P(PSTR("Servo %d\t\tpos:%d\n"),active_servo+1, temp); |
|
|
|
|
cliSerial->printf_P(PSTR("Servo %d\t\tpos:%d\n"),active_servo+1, temp); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case 'r': |
|
|
|
@ -615,28 +640,28 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
@@ -615,28 +640,28 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
if( temp > -500 && temp < 500 ) { |
|
|
|
|
heli_get_servo(active_servo)->radio_trim = 1500 + temp; |
|
|
|
|
motors.init_swash(); |
|
|
|
|
Serial.printf_P(PSTR("Servo %d\t\ttrim:%d\n"),active_servo+1, 1500 + temp); |
|
|
|
|
cliSerial->printf_P(PSTR("Servo %d\t\ttrim:%d\n"),active_servo+1, 1500 + temp); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case 'u': |
|
|
|
|
case 'U': |
|
|
|
|
temp = 0; |
|
|
|
|
// delay up to 2 seconds for servo type from user |
|
|
|
|
while( !Serial.available() && temp < 20 ) { |
|
|
|
|
while( !cliSerial->available() && temp < 20 ) { |
|
|
|
|
temp++; |
|
|
|
|
delay(100); |
|
|
|
|
} |
|
|
|
|
if( Serial.available() ) { |
|
|
|
|
value = Serial.read(); |
|
|
|
|
if( cliSerial->available() ) { |
|
|
|
|
value = cliSerial->read(); |
|
|
|
|
if( value == 'a' || value == 'A' ) { |
|
|
|
|
g.rc_speed.set_and_save(AP_MOTORS_HELI_SPEED_ANALOG_SERVOS); |
|
|
|
|
//motors._speed_hz = AP_MOTORS_HELI_SPEED_ANALOG_SERVOS; // need to force this update to take effect immediately |
|
|
|
|
Serial.printf_P(PSTR("Analog Servo %dhz\n"),(int)g.rc_speed); |
|
|
|
|
cliSerial->printf_P(PSTR("Analog Servo %dhz\n"),(int)g.rc_speed); |
|
|
|
|
} |
|
|
|
|
if( value == 'd' || value == 'D' ) { |
|
|
|
|
g.rc_speed.set_and_save(AP_MOTORS_HELI_SPEED_ANALOG_SERVOS); |
|
|
|
|
//motors._speed_hz = AP_MOTORS_HELI_SPEED_ANALOG_SERVOS; // need to force this update to take effect immediately |
|
|
|
|
Serial.printf_P(PSTR("Digital Servo %dhz\n"),(int)g.rc_speed); |
|
|
|
|
cliSerial->printf_P(PSTR("Digital Servo %dhz\n"),(int)g.rc_speed); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
@ -696,7 +721,7 @@ setup_gyro(uint8_t argc, const Menu::arg *argv)
@@ -696,7 +721,7 @@ setup_gyro(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
motors.ext_gyro_gain.save(); |
|
|
|
|
|
|
|
|
|
}else{ |
|
|
|
|
Serial.printf_P(PSTR("\nOp:[on, off] gain\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nOp:[on, off] gain\n")); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
report_gyro(); |
|
|
|
@ -724,7 +749,7 @@ setup_optflow(uint8_t argc, const Menu::arg *argv)
@@ -724,7 +749,7 @@ setup_optflow(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
g.optflow_enabled = false; |
|
|
|
|
|
|
|
|
|
}else{ |
|
|
|
|
Serial.printf_P(PSTR("\nOp:[on, off]\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nOp:[on, off]\n")); |
|
|
|
|
report_optflow(); |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
@ -743,11 +768,11 @@ setup_optflow(uint8_t argc, const Menu::arg *argv)
@@ -743,11 +768,11 @@ setup_optflow(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
|
|
|
|
|
static void report_batt_monitor() |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("\nBatt Mon:\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nBatt Mon:\n")); |
|
|
|
|
print_divider(); |
|
|
|
|
if(g.battery_monitoring == 0) print_enabled(false); |
|
|
|
|
if(g.battery_monitoring == 3) Serial.printf_P(PSTR("volts")); |
|
|
|
|
if(g.battery_monitoring == 4) Serial.printf_P(PSTR("volts and cur")); |
|
|
|
|
if(g.battery_monitoring == 3) cliSerial->printf_P(PSTR("volts")); |
|
|
|
|
if(g.battery_monitoring == 4) cliSerial->printf_P(PSTR("volts and cur")); |
|
|
|
|
print_blanks(2); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -766,39 +791,39 @@ static void report_wp(byte index = 255)
@@ -766,39 +791,39 @@ static void report_wp(byte index = 255)
|
|
|
|
|
|
|
|
|
|
static void report_sonar() |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("Sonar\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Sonar\n")); |
|
|
|
|
print_divider(); |
|
|
|
|
print_enabled(g.sonar_enabled.get()); |
|
|
|
|
Serial.printf_P(PSTR("Type: %d (0=XL, 1=LV, 2=XLL, 3=HRLV)"), (int)g.sonar_type); |
|
|
|
|
cliSerial->printf_P(PSTR("Type: %d (0=XL, 1=LV, 2=XLL, 3=HRLV)"), (int)g.sonar_type); |
|
|
|
|
print_blanks(2); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
static void report_frame() |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("Frame\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Frame\n")); |
|
|
|
|
print_divider(); |
|
|
|
|
|
|
|
|
|
#if FRAME_CONFIG == QUAD_FRAME |
|
|
|
|
Serial.printf_P(PSTR("Quad frame\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Quad frame\n")); |
|
|
|
|
#elif FRAME_CONFIG == TRI_FRAME |
|
|
|
|
Serial.printf_P(PSTR("TRI frame\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("TRI frame\n")); |
|
|
|
|
#elif FRAME_CONFIG == HEXA_FRAME |
|
|
|
|
Serial.printf_P(PSTR("Hexa frame\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Hexa frame\n")); |
|
|
|
|
#elif FRAME_CONFIG == Y6_FRAME |
|
|
|
|
Serial.printf_P(PSTR("Y6 frame\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Y6 frame\n")); |
|
|
|
|
#elif FRAME_CONFIG == OCTA_FRAME |
|
|
|
|
Serial.printf_P(PSTR("Octa frame\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Octa frame\n")); |
|
|
|
|
#elif FRAME_CONFIG == HELI_FRAME |
|
|
|
|
Serial.printf_P(PSTR("Heli frame\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Heli frame\n")); |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
#if FRAME_CONFIG != HELI_FRAME |
|
|
|
|
if(g.frame_orientation == X_FRAME) |
|
|
|
|
Serial.printf_P(PSTR("X mode\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("X mode\n")); |
|
|
|
|
else if(g.frame_orientation == PLUS_FRAME) |
|
|
|
|
Serial.printf_P(PSTR("+ mode\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("+ mode\n")); |
|
|
|
|
else if(g.frame_orientation == V_FRAME) |
|
|
|
|
Serial.printf_P(PSTR("V mode\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("V mode\n")); |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
print_blanks(2); |
|
|
|
@ -806,7 +831,7 @@ static void report_frame()
@@ -806,7 +831,7 @@ static void report_frame()
|
|
|
|
|
|
|
|
|
|
static void report_radio() |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("Radio\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Radio\n")); |
|
|
|
|
print_divider(); |
|
|
|
|
// radio |
|
|
|
|
print_radio_values(); |
|
|
|
@ -815,7 +840,7 @@ static void report_radio()
@@ -815,7 +840,7 @@ static void report_radio()
|
|
|
|
|
|
|
|
|
|
static void report_ins() |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("INS\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("INS\n")); |
|
|
|
|
print_divider(); |
|
|
|
|
|
|
|
|
|
print_gyro_offsets(); |
|
|
|
@ -825,19 +850,19 @@ static void report_ins()
@@ -825,19 +850,19 @@ static void report_ins()
|
|
|
|
|
|
|
|
|
|
static void report_compass() |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("Compass\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Compass\n")); |
|
|
|
|
print_divider(); |
|
|
|
|
|
|
|
|
|
print_enabled(g.compass_enabled); |
|
|
|
|
|
|
|
|
|
// mag declination |
|
|
|
|
Serial.printf_P(PSTR("Mag Dec: %4.4f\n"), |
|
|
|
|
cliSerial->printf_P(PSTR("Mag Dec: %4.4f\n"), |
|
|
|
|
degrees(compass.get_declination())); |
|
|
|
|
|
|
|
|
|
Vector3f offsets = compass.get_offsets(); |
|
|
|
|
|
|
|
|
|
// mag offsets |
|
|
|
|
Serial.printf_P(PSTR("Mag off: %4.4f, %4.4f, %4.4f"), |
|
|
|
|
cliSerial->printf_P(PSTR("Mag off: %4.4f, %4.4f, %4.4f"), |
|
|
|
|
offsets.x, |
|
|
|
|
offsets.y, |
|
|
|
|
offsets.z); |
|
|
|
@ -846,7 +871,7 @@ static void report_compass()
@@ -846,7 +871,7 @@ static void report_compass()
|
|
|
|
|
|
|
|
|
|
static void report_flight_modes() |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("Flight modes\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Flight modes\n")); |
|
|
|
|
print_divider(); |
|
|
|
|
|
|
|
|
|
for(int16_t i = 0; i < 6; i++ ) { |
|
|
|
@ -858,13 +883,13 @@ static void report_flight_modes()
@@ -858,13 +883,13 @@ static void report_flight_modes()
|
|
|
|
|
void report_optflow() |
|
|
|
|
{ |
|
|
|
|
#if OPTFLOW == ENABLED |
|
|
|
|
Serial.printf_P(PSTR("OptFlow\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("OptFlow\n")); |
|
|
|
|
print_divider(); |
|
|
|
|
|
|
|
|
|
print_enabled(g.optflow_enabled); |
|
|
|
|
|
|
|
|
|
// field of view |
|
|
|
|
//Serial.printf_P(PSTR("FOV: %4.0f\n"), |
|
|
|
|
//cliSerial->printf_P(PSTR("FOV: %4.0f\n"), |
|
|
|
|
// degrees(g.optflow_fov)); |
|
|
|
|
|
|
|
|
|
print_blanks(2); |
|
|
|
@ -874,22 +899,22 @@ void report_optflow()
@@ -874,22 +899,22 @@ void report_optflow()
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME |
|
|
|
|
static void report_heli() |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("Heli\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Heli\n")); |
|
|
|
|
print_divider(); |
|
|
|
|
|
|
|
|
|
// main servo settings |
|
|
|
|
Serial.printf_P(PSTR("Servo \tpos \tmin \tmax \trev\n")); |
|
|
|
|
Serial.printf_P(PSTR("1:\t%d \t%d \t%d \t%d\n"),(int)motors.servo1_pos, (int)motors._servo_1->radio_min, (int)motors._servo_1->radio_max, (int)motors._servo_1->get_reverse()); |
|
|
|
|
Serial.printf_P(PSTR("2:\t%d \t%d \t%d \t%d\n"),(int)motors.servo2_pos, (int)motors._servo_2->radio_min, (int)motors._servo_2->radio_max, (int)motors._servo_2->get_reverse()); |
|
|
|
|
Serial.printf_P(PSTR("3:\t%d \t%d \t%d \t%d\n"),(int)motors.servo3_pos, (int)motors._servo_3->radio_min, (int)motors._servo_3->radio_max, (int)motors._servo_3->get_reverse()); |
|
|
|
|
Serial.printf_P(PSTR("tail:\t\t%d \t%d \t%d\n"), (int)motors._servo_4->radio_min, (int)motors._servo_4->radio_max, (int)motors._servo_4->get_reverse()); |
|
|
|
|
cliSerial->printf_P(PSTR("Servo \tpos \tmin \tmax \trev\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("1:\t%d \t%d \t%d \t%d\n"),(int)motors.servo1_pos, (int)motors._servo_1->radio_min, (int)motors._servo_1->radio_max, (int)motors._servo_1->get_reverse()); |
|
|
|
|
cliSerial->printf_P(PSTR("2:\t%d \t%d \t%d \t%d\n"),(int)motors.servo2_pos, (int)motors._servo_2->radio_min, (int)motors._servo_2->radio_max, (int)motors._servo_2->get_reverse()); |
|
|
|
|
cliSerial->printf_P(PSTR("3:\t%d \t%d \t%d \t%d\n"),(int)motors.servo3_pos, (int)motors._servo_3->radio_min, (int)motors._servo_3->radio_max, (int)motors._servo_3->get_reverse()); |
|
|
|
|
cliSerial->printf_P(PSTR("tail:\t\t%d \t%d \t%d\n"), (int)motors._servo_4->radio_min, (int)motors._servo_4->radio_max, (int)motors._servo_4->get_reverse()); |
|
|
|
|
|
|
|
|
|
Serial.printf_P(PSTR("roll max: \t%d\n"), (int)motors.roll_max); |
|
|
|
|
Serial.printf_P(PSTR("pitch max: \t%d\n"), (int)motors.pitch_max); |
|
|
|
|
Serial.printf_P(PSTR("coll min:\t%d\t mid:%d\t max:%d\n"),(int)motors.collective_min, (int)motors.collective_mid, (int)motors.collective_max); |
|
|
|
|
cliSerial->printf_P(PSTR("roll max: \t%d\n"), (int)motors.roll_max); |
|
|
|
|
cliSerial->printf_P(PSTR("pitch max: \t%d\n"), (int)motors.pitch_max); |
|
|
|
|
cliSerial->printf_P(PSTR("coll min:\t%d\t mid:%d\t max:%d\n"),(int)motors.collective_min, (int)motors.collective_mid, (int)motors.collective_max); |
|
|
|
|
|
|
|
|
|
// calculate and print servo rate |
|
|
|
|
Serial.printf_P(PSTR("servo rate:\t%d hz\n"),(int)g.rc_speed); |
|
|
|
|
cliSerial->printf_P(PSTR("servo rate:\t%d hz\n"),(int)g.rc_speed); |
|
|
|
|
|
|
|
|
|
print_blanks(2); |
|
|
|
|
} |
|
|
|
@ -897,12 +922,12 @@ static void report_heli()
@@ -897,12 +922,12 @@ static void report_heli()
|
|
|
|
|
static void report_gyro() |
|
|
|
|
{ |
|
|
|
|
|
|
|
|
|
Serial.printf_P(PSTR("Gyro:\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("Gyro:\n")); |
|
|
|
|
print_divider(); |
|
|
|
|
|
|
|
|
|
print_enabled( motors.ext_gyro_enabled ); |
|
|
|
|
if( motors.ext_gyro_enabled ) |
|
|
|
|
Serial.printf_P(PSTR("gain: %d"),(int)motors.ext_gyro_gain); |
|
|
|
|
cliSerial->printf_P(PSTR("gain: %d"),(int)motors.ext_gyro_gain); |
|
|
|
|
|
|
|
|
|
print_blanks(2); |
|
|
|
|
} |
|
|
|
@ -916,7 +941,7 @@ static void report_gyro()
@@ -916,7 +941,7 @@ static void report_gyro()
|
|
|
|
|
/*static void |
|
|
|
|
* print_PID(PI * pid) |
|
|
|
|
* { |
|
|
|
|
* Serial.printf_P(PSTR("P: %4.2f, I:%4.2f, IMAX:%ld\n"), |
|
|
|
|
* cliSerial->printf_P(PSTR("P: %4.2f, I:%4.2f, IMAX:%ld\n"), |
|
|
|
|
* pid->kP(), |
|
|
|
|
* pid->kI(), |
|
|
|
|
* (long)pid->imax()); |
|
|
|
@ -926,32 +951,32 @@ static void report_gyro()
@@ -926,32 +951,32 @@ static void report_gyro()
|
|
|
|
|
static void |
|
|
|
|
print_radio_values() |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("CH1: %d | %d\n"), (int)g.rc_1.radio_min, (int)g.rc_1.radio_max); |
|
|
|
|
Serial.printf_P(PSTR("CH2: %d | %d\n"), (int)g.rc_2.radio_min, (int)g.rc_2.radio_max); |
|
|
|
|
Serial.printf_P(PSTR("CH3: %d | %d\n"), (int)g.rc_3.radio_min, (int)g.rc_3.radio_max); |
|
|
|
|
Serial.printf_P(PSTR("CH4: %d | %d\n"), (int)g.rc_4.radio_min, (int)g.rc_4.radio_max); |
|
|
|
|
Serial.printf_P(PSTR("CH5: %d | %d\n"), (int)g.rc_5.radio_min, (int)g.rc_5.radio_max); |
|
|
|
|
Serial.printf_P(PSTR("CH6: %d | %d\n"), (int)g.rc_6.radio_min, (int)g.rc_6.radio_max); |
|
|
|
|
Serial.printf_P(PSTR("CH7: %d | %d\n"), (int)g.rc_7.radio_min, (int)g.rc_7.radio_max); |
|
|
|
|
//Serial.printf_P(PSTR("CH8: %d | %d\n"), (int)g.rc_8.radio_min, (int)g.rc_8.radio_max); |
|
|
|
|
cliSerial->printf_P(PSTR("CH1: %d | %d\n"), (int)g.rc_1.radio_min, (int)g.rc_1.radio_max); |
|
|
|
|
cliSerial->printf_P(PSTR("CH2: %d | %d\n"), (int)g.rc_2.radio_min, (int)g.rc_2.radio_max); |
|
|
|
|
cliSerial->printf_P(PSTR("CH3: %d | %d\n"), (int)g.rc_3.radio_min, (int)g.rc_3.radio_max); |
|
|
|
|
cliSerial->printf_P(PSTR("CH4: %d | %d\n"), (int)g.rc_4.radio_min, (int)g.rc_4.radio_max); |
|
|
|
|
cliSerial->printf_P(PSTR("CH5: %d | %d\n"), (int)g.rc_5.radio_min, (int)g.rc_5.radio_max); |
|
|
|
|
cliSerial->printf_P(PSTR("CH6: %d | %d\n"), (int)g.rc_6.radio_min, (int)g.rc_6.radio_max); |
|
|
|
|
cliSerial->printf_P(PSTR("CH7: %d | %d\n"), (int)g.rc_7.radio_min, (int)g.rc_7.radio_max); |
|
|
|
|
//cliSerial->printf_P(PSTR("CH8: %d | %d\n"), (int)g.rc_8.radio_min, (int)g.rc_8.radio_max); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
static void |
|
|
|
|
print_switch(byte p, byte m, bool b) |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("Pos %d:\t"),p); |
|
|
|
|
cliSerial->printf_P(PSTR("Pos %d:\t"),p); |
|
|
|
|
print_flight_mode(m); |
|
|
|
|
Serial.printf_P(PSTR(",\t\tSimple: ")); |
|
|
|
|
cliSerial->printf_P(PSTR(",\t\tSimple: ")); |
|
|
|
|
if(b) |
|
|
|
|
Serial.printf_P(PSTR("ON\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("ON\n")); |
|
|
|
|
else |
|
|
|
|
Serial.printf_P(PSTR("OFF\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("OFF\n")); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
static void |
|
|
|
|
print_done() |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("\nSaved\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nSaved\n")); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
@ -959,13 +984,13 @@ static void zero_eeprom(void)
@@ -959,13 +984,13 @@ static void zero_eeprom(void)
|
|
|
|
|
{ |
|
|
|
|
byte b = 0; |
|
|
|
|
|
|
|
|
|
Serial.printf_P(PSTR("\nErasing EEPROM\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nErasing EEPROM\n")); |
|
|
|
|
|
|
|
|
|
for (uintptr_t i = 0; i < EEPROM_MAX_ADDR; i++) { |
|
|
|
|
eeprom_write_byte((uint8_t *) i, b); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
Serial.printf_P(PSTR("done\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("done\n")); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
static void |
|
|
|
@ -973,7 +998,7 @@ print_accel_offsets_and_scaling(void)
@@ -973,7 +998,7 @@ print_accel_offsets_and_scaling(void)
|
|
|
|
|
{ |
|
|
|
|
Vector3f accel_offsets = ins.get_accel_offsets(); |
|
|
|
|
Vector3f accel_scale = ins.get_accel_scale(); |
|
|
|
|
Serial.printf_P(PSTR("A_off: %4.2f, %4.2f, %4.2f\tA_scale: %4.2f, %4.2f, %4.2f\n"), |
|
|
|
|
cliSerial->printf_P(PSTR("A_off: %4.2f, %4.2f, %4.2f\tA_scale: %4.2f, %4.2f, %4.2f\n"), |
|
|
|
|
(float)accel_offsets.x, // Pitch |
|
|
|
|
(float)accel_offsets.y, // Roll |
|
|
|
|
(float)accel_offsets.z, // YAW |
|
|
|
@ -986,7 +1011,7 @@ static void
@@ -986,7 +1011,7 @@ static void
|
|
|
|
|
print_gyro_offsets(void) |
|
|
|
|
{ |
|
|
|
|
Vector3f gyro_offsets = ins.get_gyro_offsets(); |
|
|
|
|
Serial.printf_P(PSTR("G_off: %4.2f, %4.2f, %4.2f\n"), |
|
|
|
|
cliSerial->printf_P(PSTR("G_off: %4.2f, %4.2f, %4.2f\n"), |
|
|
|
|
(float)gyro_offsets.x, |
|
|
|
|
(float)gyro_offsets.y, |
|
|
|
|
(float)gyro_offsets.z); |
|
|
|
@ -1014,11 +1039,11 @@ static int16_t read_num_from_serial() {
@@ -1014,11 +1039,11 @@ static int16_t read_num_from_serial() {
|
|
|
|
|
char data[5] = ""; |
|
|
|
|
|
|
|
|
|
do { |
|
|
|
|
if (Serial.available() == 0) { |
|
|
|
|
if (cliSerial->available() == 0) { |
|
|
|
|
delay(10); |
|
|
|
|
timeout++; |
|
|
|
|
}else{ |
|
|
|
|
data[index] = Serial.read(); |
|
|
|
|
data[index] = cliSerial->read(); |
|
|
|
|
timeout = 0; |
|
|
|
|
index++; |
|
|
|
|
} |
|
|
|
@ -1035,7 +1060,7 @@ print_blanks(int16_t num)
@@ -1035,7 +1060,7 @@ print_blanks(int16_t num)
|
|
|
|
|
{ |
|
|
|
|
while(num > 0) { |
|
|
|
|
num--; |
|
|
|
|
Serial.println(""); |
|
|
|
|
cliSerial->println(""); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -1044,11 +1069,11 @@ static bool
@@ -1044,11 +1069,11 @@ static bool
|
|
|
|
|
wait_for_yes() |
|
|
|
|
{ |
|
|
|
|
int c; |
|
|
|
|
Serial.flush(); |
|
|
|
|
Serial.printf_P(PSTR("Y to save\n")); |
|
|
|
|
cliSerial->flush(); |
|
|
|
|
cliSerial->printf_P(PSTR("Y to save\n")); |
|
|
|
|
|
|
|
|
|
do { |
|
|
|
|
c = Serial.read(); |
|
|
|
|
c = cliSerial->read(); |
|
|
|
|
} while (-1 == c); |
|
|
|
|
|
|
|
|
|
if (('y' == c) || ('Y' == c)) |
|
|
|
@ -1061,18 +1086,18 @@ static void
@@ -1061,18 +1086,18 @@ static void
|
|
|
|
|
print_divider(void) |
|
|
|
|
{ |
|
|
|
|
for (int i = 0; i < 40; i++) { |
|
|
|
|
Serial.print_P(PSTR("-")); |
|
|
|
|
cliSerial->print_P(PSTR("-")); |
|
|
|
|
} |
|
|
|
|
Serial.println(); |
|
|
|
|
cliSerial->println(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
static void print_enabled(bool b) |
|
|
|
|
{ |
|
|
|
|
if(b) |
|
|
|
|
Serial.print_P(PSTR("en")); |
|
|
|
|
cliSerial->print_P(PSTR("en")); |
|
|
|
|
else |
|
|
|
|
Serial.print_P(PSTR("dis")); |
|
|
|
|
Serial.print_P(PSTR("abled\n")); |
|
|
|
|
cliSerial->print_P(PSTR("dis")); |
|
|
|
|
cliSerial->print_P(PSTR("abled\n")); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
@ -1094,7 +1119,7 @@ static void print_wp(struct Location *cmd, byte index)
@@ -1094,7 +1119,7 @@ static void print_wp(struct Location *cmd, byte index)
|
|
|
|
|
//float t1 = (float)cmd->lat / t7; |
|
|
|
|
//float t2 = (float)cmd->lng / t7; |
|
|
|
|
|
|
|
|
|
Serial.printf_P(PSTR("cmd#: %d | %d, %d, %d, %ld, %ld, %ld\n"), |
|
|
|
|
cliSerial->printf_P(PSTR("cmd#: %d | %d, %d, %d, %ld, %ld, %ld\n"), |
|
|
|
|
index, |
|
|
|
|
cmd->id, |
|
|
|
|
cmd->options, |
|
|
|
@ -1104,7 +1129,7 @@ static void print_wp(struct Location *cmd, byte index)
@@ -1104,7 +1129,7 @@ static void print_wp(struct Location *cmd, byte index)
|
|
|
|
|
cmd->lng); |
|
|
|
|
|
|
|
|
|
/* |
|
|
|
|
Serial.printf_P(PSTR("cmd#: %d id:%d op:%d p1:%d p2:%ld p3:%4.7f p4:%4.7f \n"), |
|
|
|
|
cliSerial->printf_P(PSTR("cmd#: %d id:%d op:%d p1:%d p2:%ld p3:%4.7f p4:%4.7f \n"), |
|
|
|
|
(int)index, |
|
|
|
|
(int)cmd->id, |
|
|
|
|
(int)cmd->options, |
|
|
|
@ -1117,7 +1142,7 @@ static void print_wp(struct Location *cmd, byte index)
@@ -1117,7 +1142,7 @@ static void print_wp(struct Location *cmd, byte index)
|
|
|
|
|
|
|
|
|
|
static void report_version() |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("FW Ver: %d\n"),(int)g.k_format_version); |
|
|
|
|
cliSerial->printf_P(PSTR("FW Ver: %d\n"),(int)g.k_format_version); |
|
|
|
|
print_divider(); |
|
|
|
|
print_blanks(2); |
|
|
|
|
} |
|
|
|
@ -1125,14 +1150,14 @@ static void report_version()
@@ -1125,14 +1150,14 @@ static void report_version()
|
|
|
|
|
|
|
|
|
|
static void report_tuning() |
|
|
|
|
{ |
|
|
|
|
Serial.printf_P(PSTR("\nTUNE:\n")); |
|
|
|
|
cliSerial->printf_P(PSTR("\nTUNE:\n")); |
|
|
|
|
print_divider(); |
|
|
|
|
if (g.radio_tuning == 0) { |
|
|
|
|
print_enabled(g.radio_tuning.get()); |
|
|
|
|
}else{ |
|
|
|
|
float low = (float)g.radio_tuning_low.get() / 1000; |
|
|
|
|
float high = (float)g.radio_tuning_high.get() / 1000; |
|
|
|
|
Serial.printf_P(PSTR(" %d, Low:%1.4f, High:%1.4f\n"),(int)g.radio_tuning.get(), low, high); |
|
|
|
|
cliSerial->printf_P(PSTR(" %d, Low:%1.4f, High:%1.4f\n"),(int)g.radio_tuning.get(), low, high); |
|
|
|
|
} |
|
|
|
|
print_blanks(2); |
|
|
|
|
} |
|
|
|
|