mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-29 20:18:31 -04:00
AP_MotorsMulticopter: minor comment update
This commit is contained in:
parent
818965fa57
commit
71d1818103
@ -379,6 +379,7 @@ void AP_MotorsMulticopter::update_throttle_hover(float dt)
|
||||
}
|
||||
}
|
||||
|
||||
// run spool logic
|
||||
void AP_MotorsMulticopter::output_logic()
|
||||
{
|
||||
// force desired and current spool mode if disarmed or not interlocked
|
||||
|
@ -75,7 +75,7 @@ public:
|
||||
// get_batt_resistance - get battery resistance approximation - for logging purposes only
|
||||
float get_batt_resistance() const { return _batt_resistance; }
|
||||
|
||||
// get_throttle_limit - throttle limit ratio - for logging purposes only
|
||||
// get throttle limit imposed by battery current limiting. This is a number from 0 ~ 1 where 0 means hover throttle, 1 means the hover throttle
|
||||
float get_throttle_limit() const { return _throttle_limit; }
|
||||
|
||||
// returns maximum thrust in the range 0 to 1
|
||||
|
Loading…
Reference in New Issue
Block a user