mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
made Yaw work like Roll and Pitch
This commit is contained in:
parent
9f8d7d5076
commit
19ab0f481e
@ -1366,12 +1366,11 @@ static void update_GPS(void)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void update_yaw_mode(void)
|
||||
{
|
||||
switch(yaw_mode){
|
||||
case YAW_ACRO:
|
||||
g.rc_4.servo_out = get_rate_yaw(g.rc_4.control_in);
|
||||
g.rc_4.servo_out = get_acro_yaw(g.rc_4.control_in);
|
||||
return;
|
||||
break;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user