mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-29 20:18:31 -04:00
This allows users to test the Auto_throttle hold or cruise value
This commit is contained in:
parent
46ef246e67
commit
3ebed0b278
@ -64,4 +64,10 @@
|
||||
#define USERHOOK_VARIABLES "UserVariables.h"
|
||||
|
||||
|
||||
// to enable, set to 1
|
||||
// to disable, set to 0
|
||||
#define AUTO_THROTTLE_HOLD 1
|
||||
|
||||
|
||||
|
||||
//# define LOGGING_ENABLED DISABLED
|
@ -1494,6 +1494,10 @@ void update_throttle_mode(void)
|
||||
{
|
||||
int16_t throttle_out;
|
||||
|
||||
#if AUTO_THROTTLE_HOLD != 0
|
||||
static float throttle_avg = THROTTLE_CRUISE;
|
||||
#endif
|
||||
|
||||
switch(throttle_mode){
|
||||
case THROTTLE_MANUAL:
|
||||
if (g.rc_3.control_in > 0){
|
||||
@ -1508,11 +1512,13 @@ void update_throttle_mode(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AUTO_THROTTLE_HOLD != 0
|
||||
// calc average throttle
|
||||
if ((g.rc_3.control_in > MINIMUM_THROTTLE)){
|
||||
//throttle_avg = throttle_avg * .98 + rc_3.control_in * .02;
|
||||
//g.throttle_cruise = throttle_avg;
|
||||
if ((g.rc_3.control_in > MINIMUM_THROTTLE) && abs(climb_rate) < 60){
|
||||
throttle_avg = throttle_avg * .98 + (float)g.rc_3.control_in * .02;
|
||||
g.throttle_cruise = throttle_avg;
|
||||
}
|
||||
#endif
|
||||
|
||||
// Code to manage the Copter state
|
||||
if ((millis() - takeoff_timer) > 5000){
|
||||
|
@ -121,6 +121,8 @@ static void init_disarm_motors()
|
||||
motor_armed = false;
|
||||
compass.save_offsets();
|
||||
|
||||
g.throttle_cruise.save();
|
||||
|
||||
// we are not in the air
|
||||
takeoff_complete = false;
|
||||
|
||||
|
@ -616,12 +616,14 @@ static void update_throttle_cruise()
|
||||
static void
|
||||
init_throttle_cruise()
|
||||
{
|
||||
#if AUTO_THROTTLE_HOLD == 0
|
||||
// are we moving from manual throttle to auto_throttle?
|
||||
if((old_control_mode <= STABILIZE) && (g.rc_3.control_in > MINIMUM_THROTTLE)){
|
||||
g.pi_throttle.reset_I();
|
||||
g.pi_alt_hold.reset_I();
|
||||
g.throttle_cruise.set_and_save(g.rc_3.control_in);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#if CLI_SLIDER_ENABLED == ENABLED && CLI_ENABLED == ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user