mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: correct circle rate tuning to use circle_nav
This commit is contained in:
parent
3e399fd830
commit
7afa0a767c
@ -1619,7 +1619,7 @@ static void tuning(){
|
||||
|
||||
case CH6_CIRCLE_RATE:
|
||||
// set circle rate
|
||||
g.circle_rate.set(g.rc_6.control_in/25-20); // allow approximately 45 degree turn rate in either direction
|
||||
circle_nav.set_rate(g.rc_6.control_in/25-20); // allow approximately 45 degree turn rate in either direction
|
||||
break;
|
||||
|
||||
case CH6_SONAR_GAIN:
|
||||
|
Loading…
Reference in New Issue
Block a user