diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index 2cdf1f5584..353b027293 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -98,6 +98,51 @@ void AP_MotorsMatrix::output_min() hal.rcout->push(); } +void AP_MotorsMatrix::output_to_motors() +{ + int8_t i; + int16_t motor_out[AP_MOTORS_MAX_NUM_MOTORS]; // final pwm values sent to the motor + + switch (_multicopter_flags.spool_mode) { + case SHUT_DOWN: + // sends minimum values out to the motors + // set motor output based on thrust requests + for (i=0; icork(); + for (i=0; ipush(); +} + // 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() diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index d118b32c75..9cf08da10b 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -42,6 +42,9 @@ public: // output_min - sends minimum values out to the motors virtual void output_min(); + // output_to_motors - sends minimum values out to the motors + virtual void output_to_motors(); + // add_motor using just position and yaw_factor (or prop direction) void add_motor(int8_t motor_num, float angle_degrees, float yaw_factor, uint8_t testing_order);