AP_Motors: formatting fixes

This commit is contained in:
Leonard Hall 2019-04-20 10:29:40 +09:30 committed by Randy Mackay
parent 4321a987f2
commit 77f8ec9f43
8 changed files with 283 additions and 288 deletions

View File

@ -26,7 +26,6 @@
extern const AP_HAL::HAL& hal;
// init
void AP_MotorsCoax::init(motor_frame_class frame_class, motor_frame_type frame_type)
{

View File

@ -111,7 +111,6 @@ void AP_MotorsMatrix::output_to_motors()
}
}
// get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t AP_MotorsMatrix::get_motor_mask()

View File

@ -257,7 +257,6 @@ void AP_MotorsMulticopter::output_boost_throttle(void)
}
}
// sends minimum values out to the motors
void AP_MotorsMulticopter::output_min()
{
@ -711,8 +710,7 @@ void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask, float r
*/
float diff_thrust = get_roll_factor(i) * rudder_dt * 0.5f;
set_actuator_with_slew(_actuator[i], thrust_to_actuator(thrust + diff_thrust));
int16_t pwm_output = get_pwm_output_min() +
(get_pwm_output_max()-get_pwm_output_min()) * _actuator[i];
int16_t pwm_output = get_pwm_output_min() + (get_pwm_output_max() - get_pwm_output_min()) * _actuator[i];
rc_write(i, pwm_output);
} else {
rc_write(i, get_pwm_output_min());

View File

@ -26,7 +26,6 @@
extern const AP_HAL::HAL& hal;
// init
void AP_MotorsSingle::init(motor_frame_class frame_class, motor_frame_type frame_type)
{