mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
2.0.25
changed Yaw to be offset from current angle to avoid the kick back. Made minimum motor speed user settable, upped to 13% (130) tweaked alt hold D to be higher and P to be slightly lower. git-svn-id: https://arducopter.googlecode.com/svn/trunk@2579 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
b70d2d4c29
commit
645d2fa333
@ -289,8 +289,8 @@ output_yaw_with_hold(boolean hold)
|
||||
// re-define nav_yaw if we have stick input
|
||||
if(g.rc_4.control_in != 0){
|
||||
// set nav_yaw + or - the current location
|
||||
//nav_yaw = (long)g.rc_4.control_in + dcm.yaw_sensor;
|
||||
nav_yaw += (long)(g.rc_4.control_in / 90);
|
||||
nav_yaw = (long)g.rc_4.control_in + dcm.yaw_sensor;
|
||||
//nav_yaw += (long)(g.rc_4.control_in / 90);
|
||||
}
|
||||
|
||||
// we need to wrap our value so we can be 0 to 360 (*100)
|
||||
|
@ -246,6 +246,10 @@
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef MINIMUM_THROTTLE
|
||||
# define MINIMUM_THROTTLE 130
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// STARTUP BEHAVIOUR
|
||||
@ -424,13 +428,13 @@
|
||||
// Throttle control gains
|
||||
//
|
||||
#ifndef THROTTLE_BARO_P
|
||||
# define THROTTLE_BARO_P 0.35 // trying a lower val
|
||||
# define THROTTLE_BARO_P 0.3 // trying a lower val
|
||||
#endif
|
||||
#ifndef THROTTLE_BARO_I
|
||||
# define THROTTLE_BARO_I 0.05 //with 4m error, 12.5s windup
|
||||
# define THROTTLE_BARO_I 0.04 //with 4m error, 12.5s windup
|
||||
#endif
|
||||
#ifndef THROTTLE_BARO_D
|
||||
# define THROTTLE_BARO_D 0.3 // upped with filter
|
||||
# define THROTTLE_BARO_D 0.35 // upped with filter
|
||||
#endif
|
||||
#ifndef THROTTLE_BARO_IMAX
|
||||
# define THROTTLE_BARO_IMAX 30
|
||||
|
@ -11,7 +11,7 @@ void output_motors_armed()
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, 1000);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + 90;
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
||||
g.rc_1.calc_pwm();
|
||||
g.rc_2.calc_pwm();
|
||||
|
@ -11,7 +11,7 @@ void output_motors_armed()
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, 1000);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + 90;
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
||||
g.rc_1.calc_pwm();
|
||||
g.rc_2.calc_pwm();
|
||||
|
@ -11,7 +11,7 @@ void output_motors_armed()
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, 1000);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + 90;
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
||||
g.rc_1.calc_pwm();
|
||||
g.rc_2.calc_pwm();
|
||||
|
@ -9,7 +9,7 @@ void output_motors_armed()
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, 1000);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + 90;
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
||||
g.rc_1.calc_pwm();
|
||||
g.rc_2.calc_pwm();
|
||||
|
@ -10,7 +10,7 @@ void output_motors_armed()
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, 1000);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + 90;
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
||||
g.rc_1.calc_pwm();
|
||||
g.rc_2.calc_pwm();
|
||||
|
@ -37,7 +37,7 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
|
||||
};
|
||||
|
||||
// Create the top-level menu object.
|
||||
MENU(main_menu, "AC 2.0.24 Beta", main_menu_commands);
|
||||
MENU(main_menu, "AC 2.0.25 Beta", main_menu_commands);
|
||||
|
||||
void init_ardupilot()
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user