|
|
|
@ -117,11 +117,11 @@ void AP_MotorsSingle::output_min()
@@ -117,11 +117,11 @@ void AP_MotorsSingle::output_min()
|
|
|
|
|
{ |
|
|
|
|
// send minimum value to each motor
|
|
|
|
|
hal.rcout->cork(); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_1, _servo1.radio_trim); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_2, _servo2.radio_trim); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_3, _servo3.radio_trim); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_4, _servo4.radio_trim); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_7, _throttle_radio_min); |
|
|
|
|
rc_write(AP_MOTORS_MOT_1, _servo1.radio_trim); |
|
|
|
|
rc_write(AP_MOTORS_MOT_2, _servo2.radio_trim); |
|
|
|
|
rc_write(AP_MOTORS_MOT_3, _servo3.radio_trim); |
|
|
|
|
rc_write(AP_MOTORS_MOT_4, _servo4.radio_trim); |
|
|
|
|
rc_write(AP_MOTORS_MOT_7, _throttle_radio_min); |
|
|
|
|
hal.rcout->push(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -175,11 +175,11 @@ void AP_MotorsSingle::output_armed_not_stabilizing()
@@ -175,11 +175,11 @@ void AP_MotorsSingle::output_armed_not_stabilizing()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
hal.rcout->cork(); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_1, _servo1.radio_out); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_2, _servo2.radio_out); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_3, _servo3.radio_out); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_4, _servo4.radio_out); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_7, throttle_radio_output); |
|
|
|
|
rc_write(AP_MOTORS_MOT_1, _servo1.radio_out); |
|
|
|
|
rc_write(AP_MOTORS_MOT_2, _servo2.radio_out); |
|
|
|
|
rc_write(AP_MOTORS_MOT_3, _servo3.radio_out); |
|
|
|
|
rc_write(AP_MOTORS_MOT_4, _servo4.radio_out); |
|
|
|
|
rc_write(AP_MOTORS_MOT_7, throttle_radio_output); |
|
|
|
|
hal.rcout->push(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -234,11 +234,11 @@ void AP_MotorsSingle::output_armed_stabilizing()
@@ -234,11 +234,11 @@ void AP_MotorsSingle::output_armed_stabilizing()
|
|
|
|
|
|
|
|
|
|
// send output to each motor
|
|
|
|
|
hal.rcout->cork(); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_1, _servo1.radio_out); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_2, _servo2.radio_out); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_3, _servo3.radio_out); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_4, _servo4.radio_out); |
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_7, throttle_radio_output); |
|
|
|
|
rc_write(AP_MOTORS_MOT_1, _servo1.radio_out); |
|
|
|
|
rc_write(AP_MOTORS_MOT_2, _servo2.radio_out); |
|
|
|
|
rc_write(AP_MOTORS_MOT_3, _servo3.radio_out); |
|
|
|
|
rc_write(AP_MOTORS_MOT_4, _servo4.radio_out); |
|
|
|
|
rc_write(AP_MOTORS_MOT_7, throttle_radio_output); |
|
|
|
|
hal.rcout->push(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -263,23 +263,23 @@ void AP_MotorsSingle::output_test(uint8_t motor_seq, int16_t pwm)
@@ -263,23 +263,23 @@ void AP_MotorsSingle::output_test(uint8_t motor_seq, int16_t pwm)
|
|
|
|
|
switch (motor_seq) { |
|
|
|
|
case 1: |
|
|
|
|
// flap servo 1
|
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_1, pwm); |
|
|
|
|
rc_write(AP_MOTORS_MOT_1, pwm); |
|
|
|
|
break; |
|
|
|
|
case 2: |
|
|
|
|
// flap servo 2
|
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_2, pwm); |
|
|
|
|
rc_write(AP_MOTORS_MOT_2, pwm); |
|
|
|
|
break; |
|
|
|
|
case 3: |
|
|
|
|
// flap servo 3
|
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_3, pwm); |
|
|
|
|
rc_write(AP_MOTORS_MOT_3, pwm); |
|
|
|
|
break; |
|
|
|
|
case 4: |
|
|
|
|
// flap servo 4
|
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_4, pwm); |
|
|
|
|
rc_write(AP_MOTORS_MOT_4, pwm); |
|
|
|
|
break; |
|
|
|
|
case 5: |
|
|
|
|
// spin main motor
|
|
|
|
|
hal.rcout->write(AP_MOTORS_MOT_7, pwm); |
|
|
|
|
rc_write(AP_MOTORS_MOT_7, pwm); |
|
|
|
|
break; |
|
|
|
|
default: |
|
|
|
|
// do nothing
|
|
|
|
|