mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
Added alternate alt hold,
New ESC Calibration Routine
This commit is contained in:
parent
c00f0d3dfb
commit
7f80649566
@ -1260,8 +1260,10 @@ static void update_altitude()
|
||||
baro_alt = (baro_alt + read_barometer()) >> 1;
|
||||
|
||||
// calc the vertical accel rate
|
||||
#if CLIMB_RATE_BARO == 1
|
||||
int temp_baro_alt = (barometer._offset_press - barometer.RawPress) << 1; // invert and scale
|
||||
#if CLIMB_RATE_BARO == 0
|
||||
int temp_baro_alt = (barometer._offset_press - barometer.RawPress) << 2; // invert and scale
|
||||
temp_baro_alt = (float)temp_baro_alt * .1 + (float)old_baro_alt * .9;
|
||||
|
||||
baro_rate = (temp_baro_alt - old_baro_alt) * 10;
|
||||
old_baro_alt = temp_baro_alt;
|
||||
|
||||
|
@ -519,7 +519,7 @@
|
||||
|
||||
// RATE control
|
||||
#ifndef THROTTLE_P
|
||||
# define THROTTLE_P 0.6 //
|
||||
# define THROTTLE_P 0.5 //
|
||||
#endif
|
||||
#ifndef THROTTLE_I
|
||||
# define THROTTLE_I 0.0 //
|
||||
|
@ -69,22 +69,44 @@ static void init_rc_out()
|
||||
APM_RC.OutputCh(CH_5, 1500);
|
||||
APM_RC.OutputCh(CH_6, 1500);
|
||||
|
||||
// don't fuss if we are calibrating
|
||||
if(g.esc_calibrate == 1)
|
||||
return;
|
||||
|
||||
output_min();
|
||||
|
||||
for(byte i = 0; i < 5; i++){
|
||||
delay(20);
|
||||
read_radio();
|
||||
}
|
||||
|
||||
// sanity check
|
||||
// sanity check - prevent unconfigured radios from outputting
|
||||
if(g.rc_3.radio_min >= 1300){
|
||||
g.rc_3.radio_min = g.rc_3.radio_in;
|
||||
output_min();
|
||||
}
|
||||
|
||||
// we are full throttle
|
||||
if(g.rc_3.control_in == 800){
|
||||
if(g.esc_calibrate == 0){
|
||||
// we will enter esc_calibrate mode on next reboot
|
||||
g.esc_calibrate.set_and_save(1);
|
||||
// send miinimum throttle out to ESC
|
||||
output_min();
|
||||
// block until we restart
|
||||
while(1){
|
||||
//Serial.println("esc");
|
||||
delay(200);
|
||||
dancing_light();
|
||||
}
|
||||
}else{
|
||||
//Serial.println("esc init");
|
||||
// clear esc flag
|
||||
g.esc_calibrate.set_and_save(0);
|
||||
// block until we restart
|
||||
init_esc();
|
||||
}
|
||||
}else{
|
||||
// did we abort the calibration?
|
||||
if(g.esc_calibrate == 1)
|
||||
g.esc_calibrate.set_and_save(0);
|
||||
|
||||
// send miinimum throttle out to ESC
|
||||
output_min();
|
||||
}
|
||||
}
|
||||
|
||||
void output_min()
|
||||
|
@ -16,7 +16,6 @@ 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);
|
||||
static int8_t setup_esc (uint8_t argc, const Menu::arg *argv);
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
static int8_t setup_optflow (uint8_t argc, const Menu::arg *argv);
|
||||
#endif
|
||||
@ -36,7 +35,6 @@ const struct Menu::command setup_menu_commands[] PROGMEM = {
|
||||
{"radio", setup_radio},
|
||||
{"frame", setup_frame},
|
||||
{"motors", setup_motors},
|
||||
{"esc", setup_esc},
|
||||
{"level", setup_accel},
|
||||
{"modes", setup_flightmodes},
|
||||
{"battery", setup_batt_monitor},
|
||||
@ -230,29 +228,6 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
|
||||
return(0);
|
||||
}
|
||||
|
||||
static int8_t
|
||||
setup_esc(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
/*Serial.printf_P(PSTR("\nESC Calibration:\n"
|
||||
"-1 Unplug USB and battery\n"
|
||||
"-2 Move CLI/FLY switch to FLY mode\n"
|
||||
"-3 Move throttle to max, connect battery\n"
|
||||
"-4 After two long beeps, throttle to 0, then test\n\n"
|
||||
" Press Enter to cancel.\n"));
|
||||
*/
|
||||
Serial.printf_P(PSTR("See wiki:\n"));
|
||||
g.esc_calibrate.set_and_save(1);
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
|
||||
if(Serial.available() > 0){
|
||||
g.esc_calibrate.set_and_save(0);
|
||||
return(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static int8_t
|
||||
setup_motors(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
@ -1122,7 +1097,6 @@ static void print_enabled(boolean b)
|
||||
static void
|
||||
init_esc()
|
||||
{
|
||||
g.esc_calibrate.set_and_save(0);
|
||||
while(1){
|
||||
read_radio();
|
||||
delay(100);
|
||||
|
@ -243,7 +243,6 @@ static void init_ardupilot()
|
||||
if(g.log_bitmask != 0){
|
||||
// TODO - Here we will check on the length of the last log
|
||||
// We don't want to create a bunch of little logs due to powering on and off
|
||||
Serial.printf("start_new_log");
|
||||
start_new_log();
|
||||
}
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user