AP_MotorsCoax: remove output_armed_not_stabilizing
This commit is contained in:
parent
45a16d6dad
commit
3df52aad5f
@ -119,53 +119,7 @@ void AP_MotorsCoax::output_min()
|
||||
hal.rcout->push();
|
||||
}
|
||||
|
||||
void AP_MotorsCoax::output_armed_not_stabilizing()
|
||||
{
|
||||
int16_t throttle_radio_output; // total throttle pwm value, summed onto throttle channel minimum, typically ~1100-1900
|
||||
int16_t out_min = _throttle_radio_min + _min_throttle;
|
||||
int16_t motor_out;
|
||||
|
||||
int16_t min_thr = rel_pwm_to_thr_range(_spin_when_armed_ramped);
|
||||
|
||||
// initialize limits flags
|
||||
limit.roll_pitch = true;
|
||||
limit.yaw = true;
|
||||
limit.throttle_lower = false;
|
||||
limit.throttle_upper = false;
|
||||
|
||||
if (_throttle_control_input <= min_thr) {
|
||||
_throttle_control_input = min_thr;
|
||||
limit.throttle_lower = true;
|
||||
}
|
||||
if (_throttle_control_input >= _max_throttle) {
|
||||
_throttle_control_input = _max_throttle;
|
||||
limit.throttle_upper = true;
|
||||
}
|
||||
|
||||
throttle_radio_output = calc_throttle_radio_output();
|
||||
|
||||
motor_out = throttle_radio_output;
|
||||
|
||||
_servo1.servo_out = 0;
|
||||
_servo1.calc_pwm();
|
||||
|
||||
_servo2.servo_out = 0;
|
||||
_servo2.calc_pwm();
|
||||
|
||||
if (motor_out >= out_min) {
|
||||
motor_out = apply_thrust_curve_and_volt_scaling(motor_out, out_min, _throttle_radio_max);
|
||||
}
|
||||
|
||||
hal.rcout->cork();
|
||||
rc_write(AP_MOTORS_MOT_1, _servo1.radio_out);
|
||||
rc_write(AP_MOTORS_MOT_2, _servo2.radio_out);
|
||||
rc_write(AP_MOTORS_MOT_3, motor_out);
|
||||
rc_write(AP_MOTORS_MOT_4, motor_out);
|
||||
hal.rcout->push();
|
||||
}
|
||||
|
||||
// sends commands to the motors
|
||||
// TODO pull code that is common to output_armed_not_stabilizing into helper functions
|
||||
void AP_MotorsCoax::output_armed_stabilizing()
|
||||
{
|
||||
int16_t yaw_pwm; // yaw pwm value, initially calculated by calc_yaw_pwm() but may be modified after, +/- 400
|
||||
|
@ -59,7 +59,6 @@ public:
|
||||
protected:
|
||||
// output - sends commands to the motors
|
||||
void output_armed_stabilizing();
|
||||
void output_armed_not_stabilizing();
|
||||
void output_disarmed();
|
||||
|
||||
AP_Int8 _rev_roll; // REV Roll feedback
|
||||
|
Loading…
Reference in New Issue
Block a user