Acro fix - we had lost the scaling of Acro mode in 2.1. This restores that.
This commit is contained in:
parent
3859ff02d4
commit
f40d40b0f9
@ -1415,8 +1415,8 @@ void update_roll_pitch_mode(void)
|
|||||||
switch(roll_pitch_mode){
|
switch(roll_pitch_mode){
|
||||||
case ROLL_PITCH_ACRO:
|
case ROLL_PITCH_ACRO:
|
||||||
// ACRO does not get SIMPLE mode ability
|
// ACRO does not get SIMPLE mode ability
|
||||||
g.rc_1.servo_out = get_rate_roll(g.rc_1.control_in);
|
g.rc_1.servo_out = get_acro_roll(g.rc_1.control_in);
|
||||||
g.rc_2.servo_out = get_rate_pitch(g.rc_2.control_in);
|
g.rc_2.servo_out = get_acro_pitch(g.rc_2.control_in);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ROLL_PITCH_STABLE:
|
case ROLL_PITCH_STABLE:
|
||||||
|
@ -80,6 +80,22 @@ get_stabilize_yaw(int32_t target_angle)
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static int
|
||||||
|
get_acro_roll(int32_t target_rate)
|
||||||
|
{
|
||||||
|
target_rate = target_rate * g.pi_stabilize_roll.kP();
|
||||||
|
target_rate = constrain(target_rate, -10000, 10000);
|
||||||
|
return get_rate_roll(target_rate);
|
||||||
|
}
|
||||||
|
|
||||||
|
static int
|
||||||
|
get_acro_pitch(int32_t target_rate)
|
||||||
|
{
|
||||||
|
target_rate = target_rate * g.pi_stabilize_pitch.kP();
|
||||||
|
target_rate = constrain(target_rate, -10000, 10000);
|
||||||
|
return get_rate_pitch(target_rate);
|
||||||
|
}
|
||||||
|
|
||||||
static int
|
static int
|
||||||
get_rate_roll(int32_t target_rate)
|
get_rate_roll(int32_t target_rate)
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user