mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Motors: Corrected the parameters.
This commit is contained in:
parent
18f0fc50d5
commit
5da7ad025b
@ -82,10 +82,10 @@ void AP_MotorsSingle::output_to_motors()
|
|||||||
for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
|
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_angle(AP_MOTORS_MOT_1 + i, _spin_up_ratio * _actuator_out[i] * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
||||||
}
|
}
|
||||||
set_actuator_with_slew(_actuator[5], actuator_spin_up_to_ground_idle());
|
set_actuator_with_slew(_actuator[AP_MOTORS_MOT_5], actuator_spin_up_to_ground_idle());
|
||||||
set_actuator_with_slew(_actuator[6], actuator_spin_up_to_ground_idle());
|
set_actuator_with_slew(_actuator[AP_MOTORS_MOT_6], actuator_spin_up_to_ground_idle());
|
||||||
rc_write(AP_MOTORS_MOT_5, output_to_pwm(_actuator[5]));
|
rc_write(AP_MOTORS_MOT_5, output_to_pwm(_actuator[AP_MOTORS_MOT_5]));
|
||||||
rc_write(AP_MOTORS_MOT_6, output_to_pwm(_actuator[6]));
|
rc_write(AP_MOTORS_MOT_6, output_to_pwm(_actuator[AP_MOTORS_MOT_6]));
|
||||||
break;
|
break;
|
||||||
case SpoolState::SPOOLING_UP:
|
case SpoolState::SPOOLING_UP:
|
||||||
case SpoolState::THROTTLE_UNLIMITED:
|
case SpoolState::THROTTLE_UNLIMITED:
|
||||||
@ -94,10 +94,10 @@ void AP_MotorsSingle::output_to_motors()
|
|||||||
for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
|
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_angle(AP_MOTORS_MOT_1 + i, _actuator_out[i] * AP_MOTORS_SINGLE_SERVO_INPUT_RANGE);
|
||||||
}
|
}
|
||||||
set_actuator_with_slew(_actuator[5], thrust_to_actuator(_thrust_out));
|
set_actuator_with_slew(_actuator[AP_MOTORS_MOT_5], thrust_to_actuator(_thrust_out));
|
||||||
set_actuator_with_slew(_actuator[6], thrust_to_actuator(_thrust_out));
|
set_actuator_with_slew(_actuator[AP_MOTORS_MOT_6], thrust_to_actuator(_thrust_out));
|
||||||
rc_write(AP_MOTORS_MOT_5, output_to_pwm(_actuator[5]));
|
rc_write(AP_MOTORS_MOT_5, output_to_pwm(_actuator[AP_MOTORS_MOT_5]));
|
||||||
rc_write(AP_MOTORS_MOT_6, output_to_pwm(_actuator[6]));
|
rc_write(AP_MOTORS_MOT_6, output_to_pwm(_actuator[AP_MOTORS_MOT_6]));
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user