void AP_MotorsTri::output_to_motors() { switch (_spool_mode) { case SHUT_DOWN: // sends minimum values out to the motors rc_write(AP_MOTORS_MOT_1, get_pwm_output_min()); rc_write(AP_MOTORS_MOT_2, get_pwm_output_min()); rc_write(AP_MOTORS_MOT_4, get_pwm_output_min()); rc_write(AP_MOTORS_CH_TRI_YAW, _yaw_servo->get_trim()); break; case SPIN_WHEN_ARMED: // sends output to motors when armed but not flying rc_write(AP_MOTORS_MOT_1, calc_spin_up_to_pwm()); rc_write(AP_MOTORS_MOT_2, calc_spin_up_to_pwm()); rc_write(AP_MOTORS_MOT_4, calc_spin_up_to_pwm()); rc_write(AP_MOTORS_CH_TRI_YAW, _yaw_servo->get_trim()); break; case SPOOL_UP: case THROTTLE_UNLIMITED: case SPOOL_DOWN: // set motor output based on thrust requests rc_write(AP_MOTORS_MOT_1, calc_thrust_to_pwm(_thrust_right)); rc_write(AP_MOTORS_MOT_2, calc_thrust_to_pwm(_thrust_left)); rc_write(AP_MOTORS_MOT_4, calc_thrust_to_pwm(_thrust_rear)); rc_write(AP_MOTORS_CH_TRI_YAW, calc_yaw_radio_output(_pivot_angle, radians(_yaw_servo_angle_max_deg))); break; } }
void AP_MotorsSingle::output_to_motors() { if (!_flags.initialised_ok) { return; } switch (_spool_mode) { case SHUT_DOWN: // sends minimum values out to the motors rc_write_angle(AP_MOTORS_MOT_1, _roll_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE); rc_write_angle(AP_MOTORS_MOT_2, _pitch_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE); rc_write_angle(AP_MOTORS_MOT_3, -_roll_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE); rc_write_angle(AP_MOTORS_MOT_4, -_pitch_radio_passthrough * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE); rc_write(AP_MOTORS_MOT_5, get_pwm_output_min()); rc_write(AP_MOTORS_MOT_6, get_pwm_output_min()); break; case SPIN_WHEN_ARMED: // sends output to motors when armed but not flying for (uint8_t i=0; i<NUM_ACTUATORS; i++) { rc_write_angle(AP_MOTORS_MOT_1+i, _spin_up_ratio * _actuator_out[i] * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE); } rc_write(AP_MOTORS_MOT_5, calc_spin_up_to_pwm()); rc_write(AP_MOTORS_MOT_6, calc_spin_up_to_pwm()); break; case SPOOL_UP: case THROTTLE_UNLIMITED: case SPOOL_DOWN: // set motor output based on thrust requests for (uint8_t i=0; i<NUM_ACTUATORS; i++) { rc_write_angle(AP_MOTORS_MOT_1+i, _actuator_out[i] * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE); } rc_write(AP_MOTORS_MOT_5, calc_thrust_to_pwm(_thrust_out)); rc_write(AP_MOTORS_MOT_6, calc_thrust_to_pwm(_thrust_out)); break; } }
void AP_MotorsCoax::output_to_motors() { switch (_spool_mode) { case SHUT_DOWN: // sends minimum values out to the motors rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(_roll_radio_passthrough, _servo1)); rc_write(AP_MOTORS_MOT_2, calc_pwm_output_1to1(_pitch_radio_passthrough, _servo2)); rc_write(AP_MOTORS_MOT_3, calc_pwm_output_1to1(-_roll_radio_passthrough, _servo3)); rc_write(AP_MOTORS_MOT_4, calc_pwm_output_1to1(-_pitch_radio_passthrough, _servo4)); rc_write(AP_MOTORS_MOT_5, get_pwm_output_min()); rc_write(AP_MOTORS_MOT_6, get_pwm_output_min()); break; case SPIN_WHEN_ARMED: // sends output to motors when armed but not flying rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(_spin_up_ratio * _actuator_out[0], _servo1)); rc_write(AP_MOTORS_MOT_2, calc_pwm_output_1to1(_spin_up_ratio * _actuator_out[1], _servo2)); rc_write(AP_MOTORS_MOT_3, calc_pwm_output_1to1(_spin_up_ratio * _actuator_out[2], _servo3)); rc_write(AP_MOTORS_MOT_4, calc_pwm_output_1to1(_spin_up_ratio * _actuator_out[3], _servo4)); rc_write(AP_MOTORS_MOT_5, calc_spin_up_to_pwm()); rc_write(AP_MOTORS_MOT_6, calc_spin_up_to_pwm()); break; case SPOOL_UP: case THROTTLE_UNLIMITED: case SPOOL_DOWN: // set motor output based on thrust requests rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(_actuator_out[0], _servo1)); rc_write(AP_MOTORS_MOT_2, calc_pwm_output_1to1(_actuator_out[1], _servo2)); rc_write(AP_MOTORS_MOT_3, calc_pwm_output_1to1(_actuator_out[2], _servo3)); rc_write(AP_MOTORS_MOT_4, calc_pwm_output_1to1(_actuator_out[3], _servo4)); 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)); break; } }
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 (_spool_mode) { case SHUT_DOWN: { // sends minimum values out to the motors // set motor output based on thrust requests for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) { if (motor_enabled[i]) { if (_disarm_disable_pwm && _disarm_safety_timer == 0 && !armed()) { motor_out[i] = 0; } else { motor_out[i] = get_pwm_output_min(); } } } break; } case SPIN_WHEN_ARMED: // sends output to motors when armed but not flying for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) { if (motor_enabled[i]) { motor_out[i] = calc_spin_up_to_pwm(); } } break; case SPOOL_UP: case THROTTLE_UNLIMITED: case SPOOL_DOWN: // set motor output based on thrust requests for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) { if (motor_enabled[i]) { motor_out[i] = calc_thrust_to_pwm(_thrust_rpyt_out[i]); } } break; } // send output to each motor hal.rcout->cork(); for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) { if (motor_enabled[i]) { rc_write(i, motor_out[i]); } } hal.rcout->push(); }