mirror of https://github.com/ArduPilot/ardupilot
Copter: update "CH6 tuning" comments
This commit is contained in:
parent
a519597249
commit
0583e85145
|
@ -659,7 +659,7 @@ void Copter::three_hz_loop()
|
|||
// check for deadreckoning failsafe
|
||||
failsafe_deadreckon_check();
|
||||
|
||||
// update ch6 in flight tuning
|
||||
//update transmitter based in flight tuning
|
||||
tuning();
|
||||
|
||||
// check if avoidance should be enabled based on alt
|
||||
|
|
|
@ -68,7 +68,7 @@ void ModeCircle::run()
|
|||
}
|
||||
|
||||
// update the orbicular rate target based on pilot roll stick inputs
|
||||
// skip if using CH6 tuning knob for circle rate
|
||||
// skip if using transmitter based tuning knob for circle rate
|
||||
if (g.radio_tuning != TUNING_CIRCLE_RATE) {
|
||||
const float roll_stick = channel_roll->norm_input_dz(); // roll stick normalized -1 to 1
|
||||
|
||||
|
|
Loading…
Reference in New Issue