mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Motors: minor comment fixes
This commit is contained in:
parent
1d0ee68116
commit
ec9d7dd99e
@ -303,7 +303,7 @@ void AP_MotorsMatrix::output_armed()
|
||||
// check everything fits
|
||||
thr_adj = throttle_radio_out - out_best_thr_pwm;
|
||||
|
||||
// calc upper and lower limits of thr_adj
|
||||
// calculate upper and lower limits of thr_adj
|
||||
int16_t thr_adj_max = max(out_max_pwm-(out_best_thr_pwm+rpy_high),0);
|
||||
|
||||
// if we are increasing the throttle (situation #2 above)..
|
||||
@ -331,7 +331,7 @@ void AP_MotorsMatrix::output_armed()
|
||||
}
|
||||
|
||||
// do we need to reduce roll, pitch, yaw command
|
||||
// earlier code does not allow both limit's to be passed simultainiously with abs(_yaw_factor)<1
|
||||
// earlier code does not allow both limit's to be passed simultaneously with abs(_yaw_factor)<1
|
||||
if ((rpy_low+out_best_thr_pwm)+thr_adj < out_min_pwm){
|
||||
rpy_scale = (float)(out_min_pwm-thr_adj-out_best_thr_pwm)/rpy_low;
|
||||
// we haven't even been able to apply full roll, pitch and minimal yaw without scaling
|
||||
|
@ -209,7 +209,7 @@ void AP_Motors::output()
|
||||
}
|
||||
};
|
||||
|
||||
// setup_throttle_curve - used to linearlise thrust output by motors
|
||||
// setup_throttle_curve - used to linearise thrust output by motors
|
||||
// returns true if set up successfully
|
||||
bool AP_Motors::setup_throttle_curve()
|
||||
{
|
||||
@ -237,7 +237,7 @@ bool AP_Motors::setup_throttle_curve()
|
||||
retval = false;
|
||||
}
|
||||
|
||||
// disable throttle curve if not set-up corrrectly
|
||||
// disable throttle curve if not set-up correctly
|
||||
if( !retval ) {
|
||||
_throttle_curve_enabled = false;
|
||||
hal.console->println_P(PSTR("AP_Motors: failed to create throttle curve"));
|
||||
|
Loading…
Reference in New Issue
Block a user