mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_MotorsMulticopter: formatting fixes
This commit is contained in:
parent
6807b961e2
commit
f6eabfdab2
@ -207,7 +207,7 @@ float AP_MotorsMulticopter::apply_thrust_curve_and_volt_scaling(float thrust) co
|
||||
{
|
||||
float throttle_ratio = thrust;
|
||||
// apply thrust curve - domain 0.0 to 1.0, range 0.0 to 1.0
|
||||
if (_thrust_curve_expo > 0.0f){
|
||||
if (_thrust_curve_expo > 0.0f && !is_zero(_batt_voltage_filt.get())){
|
||||
throttle_ratio = ((_thrust_curve_expo-1.0f) + safe_sqrt((1.0f-_thrust_curve_expo)*(1.0f-_thrust_curve_expo) + 4.0f*_thrust_curve_expo*_lift_max*thrust))/(2.0f*_thrust_curve_expo*_batt_voltage_filt.get());
|
||||
}
|
||||
|
||||
@ -350,7 +350,7 @@ void AP_MotorsMulticopter::output_logic()
|
||||
|
||||
case SPIN_WHEN_ARMED: {
|
||||
// Motors should be stationary or at spin when armed.
|
||||
// Servoes should be moving to correct the current attitude.
|
||||
// Servos should be moving to correct the current attitude.
|
||||
|
||||
// set limits flags
|
||||
limit.roll_pitch = true;
|
||||
|
Loading…
Reference in New Issue
Block a user