diff --git a/libraries/AP_Motors/AP_MotorsCoax.cpp b/libraries/AP_Motors/AP_MotorsCoax.cpp index 56711844ff..0a812badc2 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.cpp +++ b/libraries/AP_Motors/AP_MotorsCoax.cpp @@ -130,6 +130,47 @@ void AP_MotorsCoax::output_min() hal.rcout->push(); } +void AP_MotorsCoax::output_to_motors() +{ + switch (_multicopter_flags.spool_mode) { + case SHUT_DOWN: + // sends minimum values out to the motors + hal.rcout->cork(); + rc_write(AP_MOTORS_MOT_1, calc_pivot_radio_output(_roll_radio_passthrough*_servo_1_reverse, _servo_1_min, _servo_1_trim, _servo_1_max)); + rc_write(AP_MOTORS_MOT_2, calc_pivot_radio_output(_pitch_radio_passthrough *_servo_2_reverse, _servo_2_min, _servo_2_trim, _servo_2_max)); + rc_write(AP_MOTORS_MOT_3, calc_pivot_radio_output(_roll_radio_passthrough*_servo_3_reverse, _servo_3_min, _servo_3_trim, _servo_3_max)); + rc_write(AP_MOTORS_MOT_4, calc_pivot_radio_output(_pitch_radio_passthrough*_servo_4_reverse, _servo_4_min, _servo_4_trim, _servo_4_max)); + rc_write(AP_MOTORS_MOT_5, _throttle_radio_min); + rc_write(AP_MOTORS_MOT_6, _throttle_radio_min); + hal.rcout->push(); + break; + case SPIN_WHEN_ARMED: + // sends output to motors when armed but not flying + hal.rcout->cork(); + rc_write(AP_MOTORS_MOT_1, calc_pivot_radio_output(_throttle_low_end_pct * _actuator_out[0]*_servo_1_reverse, _servo_1_min, _servo_1_trim, _servo_1_max)); + rc_write(AP_MOTORS_MOT_2, calc_pivot_radio_output(_throttle_low_end_pct * _actuator_out[1]*_servo_2_reverse, _servo_2_min, _servo_2_trim, _servo_2_max)); + rc_write(AP_MOTORS_MOT_3, calc_pivot_radio_output(_throttle_low_end_pct * _actuator_out[2]*_servo_3_reverse, _servo_3_min, _servo_3_trim, _servo_3_max)); + rc_write(AP_MOTORS_MOT_4, calc_pivot_radio_output(_throttle_low_end_pct * _actuator_out[3]*_servo_4_reverse, _servo_4_min, _servo_4_trim, _servo_4_max)); + rc_write(AP_MOTORS_MOT_5, constrain_int16(_throttle_radio_min + _throttle_low_end_pct * _min_throttle, _throttle_radio_min, _throttle_radio_min + _min_throttle)); + rc_write(AP_MOTORS_MOT_6, constrain_int16(_throttle_radio_min + _throttle_low_end_pct * _min_throttle, _throttle_radio_min, _throttle_radio_min + _min_throttle)); + hal.rcout->push(); + break; + case SPOOL_UP: + case THROTTLE_UNLIMITED: + case SPOOL_DOWN: + // set motor output based on thrust requests + hal.rcout->cork(); + rc_write(AP_MOTORS_MOT_1, calc_pivot_radio_output(_actuator_out[0]*_servo_1_reverse, _servo_1_min, _servo_1_trim, _servo_1_max)); + rc_write(AP_MOTORS_MOT_2, calc_pivot_radio_output(_actuator_out[1]*_servo_2_reverse, _servo_2_min, _servo_2_trim, _servo_2_max)); + rc_write(AP_MOTORS_MOT_3, calc_pivot_radio_output(_actuator_out[2]*_servo_3_reverse, _servo_3_min, _servo_3_trim, _servo_3_max)); + rc_write(AP_MOTORS_MOT_4, calc_pivot_radio_output(_actuator_out[3]*_servo_4_reverse, _servo_4_min, _servo_4_trim, _servo_4_max)); + rc_write(AP_MOTORS_MOT_5, calc_thrust_to_pwm(_thrust_yt_ccw)); + rc_write(AP_MOTORS_MOT_6, calc_thrust_to_pwm(_thrust_yt_cw)); + hal.rcout->push(); + break; + } +} + // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict uint16_t AP_MotorsCoax::get_motor_mask() diff --git a/libraries/AP_Motors/AP_MotorsCoax.h b/libraries/AP_Motors/AP_MotorsCoax.h index 159e20648e..1b5d3d58eb 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.h +++ b/libraries/AP_Motors/AP_MotorsCoax.h @@ -52,6 +52,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(); + // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict virtual uint16_t get_motor_mask();