mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Motors: removed cork/push from AP_Motors
should be done by vehicle code if needed, so that AUX servos are sent at the same time
This commit is contained in:
parent
5c028897a3
commit
2c4975ba31
@ -183,13 +183,11 @@ void AP_Motors6DOF::output_min()
|
|||||||
|
|
||||||
// fill the motor_out[] array for HIL use and send minimum value to each motor
|
// fill the motor_out[] array for HIL use and send minimum value to each motor
|
||||||
// ToDo find a field to store the minimum pwm instead of hard coding 1500
|
// ToDo find a field to store the minimum pwm instead of hard coding 1500
|
||||||
hal.rcout->cork();
|
|
||||||
for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||||
if (motor_enabled[i]) {
|
if (motor_enabled[i]) {
|
||||||
rc_write(i, 1500);
|
rc_write(i, 1500);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hal.rcout->push();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int16_t AP_Motors6DOF::calc_thrust_to_pwm(float thrust_in) const
|
int16_t AP_Motors6DOF::calc_thrust_to_pwm(float thrust_in) const
|
||||||
@ -233,13 +231,11 @@ void AP_Motors6DOF::output_to_motors()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// send output to each motor
|
// send output to each motor
|
||||||
hal.rcout->cork();
|
|
||||||
for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||||
if (motor_enabled[i]) {
|
if (motor_enabled[i]) {
|
||||||
rc_write(i, motor_out[i]);
|
rc_write(i, motor_out[i]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hal.rcout->push();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// output_armed - sends commands to the motors
|
// output_armed - sends commands to the motors
|
||||||
|
@ -89,38 +89,32 @@ void AP_MotorsCoax::output_to_motors()
|
|||||||
switch (_spool_mode) {
|
switch (_spool_mode) {
|
||||||
case SHUT_DOWN:
|
case SHUT_DOWN:
|
||||||
// sends minimum values out to the motors
|
// sends minimum values out to the motors
|
||||||
hal.rcout->cork();
|
|
||||||
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(_roll_radio_passthrough, _servo1));
|
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_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_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_4, calc_pwm_output_1to1(-_pitch_radio_passthrough, _servo4));
|
||||||
rc_write(AP_MOTORS_MOT_5, get_pwm_output_min());
|
rc_write(AP_MOTORS_MOT_5, get_pwm_output_min());
|
||||||
rc_write(AP_MOTORS_MOT_6, get_pwm_output_min());
|
rc_write(AP_MOTORS_MOT_6, get_pwm_output_min());
|
||||||
hal.rcout->push();
|
|
||||||
break;
|
break;
|
||||||
case SPIN_WHEN_ARMED:
|
case SPIN_WHEN_ARMED:
|
||||||
// sends output to motors when armed but not flying
|
// sends output to motors when armed but not flying
|
||||||
hal.rcout->cork();
|
|
||||||
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(_spin_up_ratio * _actuator_out[0], _servo1));
|
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_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_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_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_5, calc_spin_up_to_pwm());
|
||||||
rc_write(AP_MOTORS_MOT_6, calc_spin_up_to_pwm());
|
rc_write(AP_MOTORS_MOT_6, calc_spin_up_to_pwm());
|
||||||
hal.rcout->push();
|
|
||||||
break;
|
break;
|
||||||
case SPOOL_UP:
|
case SPOOL_UP:
|
||||||
case THROTTLE_UNLIMITED:
|
case THROTTLE_UNLIMITED:
|
||||||
case SPOOL_DOWN:
|
case SPOOL_DOWN:
|
||||||
// set motor output based on thrust requests
|
// set motor output based on thrust requests
|
||||||
hal.rcout->cork();
|
|
||||||
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(_actuator_out[0], _servo1));
|
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_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_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_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_5, calc_thrust_to_pwm(_thrust_yt_ccw));
|
||||||
rc_write(AP_MOTORS_MOT_6, calc_thrust_to_pwm(_thrust_yt_cw));
|
rc_write(AP_MOTORS_MOT_6, calc_thrust_to_pwm(_thrust_yt_cw));
|
||||||
hal.rcout->push();
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -543,16 +543,12 @@ void AP_MotorsHeli_Dual::move_actuators(float roll_out, float pitch_out, float c
|
|||||||
servo6_out = 2*servo6_out - 1;
|
servo6_out = 2*servo6_out - 1;
|
||||||
|
|
||||||
// actually move the servos
|
// actually move the servos
|
||||||
hal.rcout->cork();
|
|
||||||
|
|
||||||
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(servo1_out, _swash_servo_1));
|
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(servo1_out, _swash_servo_1));
|
||||||
rc_write(AP_MOTORS_MOT_2, calc_pwm_output_1to1(servo2_out, _swash_servo_2));
|
rc_write(AP_MOTORS_MOT_2, calc_pwm_output_1to1(servo2_out, _swash_servo_2));
|
||||||
rc_write(AP_MOTORS_MOT_3, calc_pwm_output_1to1(servo3_out, _swash_servo_3));
|
rc_write(AP_MOTORS_MOT_3, calc_pwm_output_1to1(servo3_out, _swash_servo_3));
|
||||||
rc_write(AP_MOTORS_MOT_4, calc_pwm_output_1to1(servo4_out, _swash_servo_4));
|
rc_write(AP_MOTORS_MOT_4, calc_pwm_output_1to1(servo4_out, _swash_servo_4));
|
||||||
rc_write(AP_MOTORS_MOT_5, calc_pwm_output_1to1(servo5_out, _swash_servo_5));
|
rc_write(AP_MOTORS_MOT_5, calc_pwm_output_1to1(servo5_out, _swash_servo_5));
|
||||||
rc_write(AP_MOTORS_MOT_6, calc_pwm_output_1to1(servo6_out, _swash_servo_6));
|
rc_write(AP_MOTORS_MOT_6, calc_pwm_output_1to1(servo6_out, _swash_servo_6));
|
||||||
|
|
||||||
hal.rcout->push();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -449,8 +449,6 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
|
|||||||
}
|
}
|
||||||
float servo3_out = ((_rollFactor[CH_3] * roll_out) + (_pitchFactor[CH_3] * pitch_out))*0.45f + _collectiveFactor[CH_3] * coll_out_scaled;
|
float servo3_out = ((_rollFactor[CH_3] * roll_out) + (_pitchFactor[CH_3] * pitch_out))*0.45f + _collectiveFactor[CH_3] * coll_out_scaled;
|
||||||
|
|
||||||
hal.rcout->cork();
|
|
||||||
|
|
||||||
// rescale from -1..1, so we can use the pwm calc that includes trim
|
// rescale from -1..1, so we can use the pwm calc that includes trim
|
||||||
servo1_out = 2*servo1_out - 1;
|
servo1_out = 2*servo1_out - 1;
|
||||||
servo2_out = 2*servo2_out - 1;
|
servo2_out = 2*servo2_out - 1;
|
||||||
@ -463,8 +461,6 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
|
|||||||
|
|
||||||
// update the yaw rate using the tail rotor/servo
|
// update the yaw rate using the tail rotor/servo
|
||||||
move_yaw(yaw_out + yaw_offset);
|
move_yaw(yaw_out + yaw_offset);
|
||||||
|
|
||||||
hal.rcout->push();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// move_yaw
|
// move_yaw
|
||||||
|
@ -126,13 +126,11 @@ void AP_MotorsMatrix::output_to_motors()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// send output to each motor
|
// send output to each motor
|
||||||
hal.rcout->cork();
|
|
||||||
for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||||
if (motor_enabled[i]) {
|
if (motor_enabled[i]) {
|
||||||
rc_write(i, motor_out[i]);
|
rc_write(i, motor_out[i]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hal.rcout->push();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -302,14 +300,12 @@ void AP_MotorsMatrix::output_test(uint8_t motor_seq, int16_t pwm)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// loop through all the possible orders spinning any motors that match that description
|
// loop through all the possible orders spinning any motors that match that description
|
||||||
hal.rcout->cork();
|
|
||||||
for (uint8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
for (uint8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||||
if (motor_enabled[i] && _test_order[i] == motor_seq) {
|
if (motor_enabled[i] && _test_order[i] == motor_seq) {
|
||||||
// turn on this motor
|
// turn on this motor
|
||||||
rc_write(i, pwm);
|
rc_write(i, pwm);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hal.rcout->push();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// add_motor
|
// add_motor
|
||||||
|
@ -582,13 +582,11 @@ void AP_MotorsMulticopter::set_throttle_passthrough_for_esc_calibration(float th
|
|||||||
if (armed()) {
|
if (armed()) {
|
||||||
uint16_t pwm_out = get_pwm_output_min() + constrain_float(throttle_input, 0.0f, 1.0f) * (get_pwm_output_max() - get_pwm_output_min());
|
uint16_t pwm_out = get_pwm_output_min() + constrain_float(throttle_input, 0.0f, 1.0f) * (get_pwm_output_max() - get_pwm_output_min());
|
||||||
// send the pilot's input directly to each enabled motor
|
// send the pilot's input directly to each enabled motor
|
||||||
hal.rcout->cork();
|
|
||||||
for (uint16_t i=0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
for (uint16_t i=0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||||
if (motor_enabled[i]) {
|
if (motor_enabled[i]) {
|
||||||
rc_write(i, pwm_out);
|
rc_write(i, pwm_out);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hal.rcout->push();
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -597,7 +595,6 @@ void AP_MotorsMulticopter::set_throttle_passthrough_for_esc_calibration(float th
|
|||||||
// the range 0 to 1
|
// the range 0 to 1
|
||||||
void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask)
|
void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask)
|
||||||
{
|
{
|
||||||
hal.rcout->cork();
|
|
||||||
for (uint8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
for (uint8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||||
if (motor_enabled[i]) {
|
if (motor_enabled[i]) {
|
||||||
int16_t motor_out;
|
int16_t motor_out;
|
||||||
@ -609,7 +606,6 @@ void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask)
|
|||||||
rc_write(i, motor_out);
|
rc_write(i, motor_out);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hal.rcout->push();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// save parameters as part of disarming
|
// save parameters as part of disarming
|
||||||
|
@ -98,38 +98,32 @@ void AP_MotorsSingle::output_to_motors()
|
|||||||
switch (_spool_mode) {
|
switch (_spool_mode) {
|
||||||
case SHUT_DOWN:
|
case SHUT_DOWN:
|
||||||
// sends minimum values out to the motors
|
// sends minimum values out to the motors
|
||||||
hal.rcout->cork();
|
|
||||||
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(_roll_radio_passthrough - _yaw_radio_passthrough, _servo1));
|
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(_roll_radio_passthrough - _yaw_radio_passthrough, _servo1));
|
||||||
rc_write(AP_MOTORS_MOT_2, calc_pwm_output_1to1(_pitch_radio_passthrough - _yaw_radio_passthrough, _servo2));
|
rc_write(AP_MOTORS_MOT_2, calc_pwm_output_1to1(_pitch_radio_passthrough - _yaw_radio_passthrough, _servo2));
|
||||||
rc_write(AP_MOTORS_MOT_3, calc_pwm_output_1to1(-_roll_radio_passthrough - _yaw_radio_passthrough, _servo3));
|
rc_write(AP_MOTORS_MOT_3, calc_pwm_output_1to1(-_roll_radio_passthrough - _yaw_radio_passthrough, _servo3));
|
||||||
rc_write(AP_MOTORS_MOT_4, calc_pwm_output_1to1(-_pitch_radio_passthrough - _yaw_radio_passthrough, _servo4));
|
rc_write(AP_MOTORS_MOT_4, calc_pwm_output_1to1(-_pitch_radio_passthrough - _yaw_radio_passthrough, _servo4));
|
||||||
rc_write(AP_MOTORS_MOT_5, get_pwm_output_min());
|
rc_write(AP_MOTORS_MOT_5, get_pwm_output_min());
|
||||||
rc_write(AP_MOTORS_MOT_6, get_pwm_output_min());
|
rc_write(AP_MOTORS_MOT_6, get_pwm_output_min());
|
||||||
hal.rcout->push();
|
|
||||||
break;
|
break;
|
||||||
case SPIN_WHEN_ARMED:
|
case SPIN_WHEN_ARMED:
|
||||||
// sends output to motors when armed but not flying
|
// sends output to motors when armed but not flying
|
||||||
hal.rcout->cork();
|
|
||||||
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(_spin_up_ratio * _actuator_out[0], _servo1));
|
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_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_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_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_5, calc_spin_up_to_pwm());
|
||||||
rc_write(AP_MOTORS_MOT_6, calc_spin_up_to_pwm());
|
rc_write(AP_MOTORS_MOT_6, calc_spin_up_to_pwm());
|
||||||
hal.rcout->push();
|
|
||||||
break;
|
break;
|
||||||
case SPOOL_UP:
|
case SPOOL_UP:
|
||||||
case THROTTLE_UNLIMITED:
|
case THROTTLE_UNLIMITED:
|
||||||
case SPOOL_DOWN:
|
case SPOOL_DOWN:
|
||||||
// set motor output based on thrust requests
|
// set motor output based on thrust requests
|
||||||
hal.rcout->cork();
|
|
||||||
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(_actuator_out[0], _servo1));
|
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_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_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_4, calc_pwm_output_1to1(_actuator_out[3], _servo4));
|
||||||
rc_write(AP_MOTORS_MOT_5, calc_thrust_to_pwm(_thrust_out));
|
rc_write(AP_MOTORS_MOT_5, calc_thrust_to_pwm(_thrust_out));
|
||||||
rc_write(AP_MOTORS_MOT_6, calc_thrust_to_pwm(_thrust_out));
|
rc_write(AP_MOTORS_MOT_6, calc_thrust_to_pwm(_thrust_out));
|
||||||
hal.rcout->push();
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -90,32 +90,26 @@ void AP_MotorsTri::output_to_motors()
|
|||||||
switch (_spool_mode) {
|
switch (_spool_mode) {
|
||||||
case SHUT_DOWN:
|
case SHUT_DOWN:
|
||||||
// sends minimum values out to the motors
|
// sends minimum values out to the motors
|
||||||
hal.rcout->cork();
|
|
||||||
rc_write(AP_MOTORS_MOT_1, get_pwm_output_min());
|
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_2, get_pwm_output_min());
|
||||||
rc_write(AP_MOTORS_MOT_4, 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());
|
rc_write(AP_MOTORS_CH_TRI_YAW, _yaw_servo->get_trim());
|
||||||
hal.rcout->push();
|
|
||||||
break;
|
break;
|
||||||
case SPIN_WHEN_ARMED:
|
case SPIN_WHEN_ARMED:
|
||||||
// sends output to motors when armed but not flying
|
// sends output to motors when armed but not flying
|
||||||
hal.rcout->cork();
|
|
||||||
rc_write(AP_MOTORS_MOT_1, calc_spin_up_to_pwm());
|
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_2, calc_spin_up_to_pwm());
|
||||||
rc_write(AP_MOTORS_MOT_4, 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());
|
rc_write(AP_MOTORS_CH_TRI_YAW, _yaw_servo->get_trim());
|
||||||
hal.rcout->push();
|
|
||||||
break;
|
break;
|
||||||
case SPOOL_UP:
|
case SPOOL_UP:
|
||||||
case THROTTLE_UNLIMITED:
|
case THROTTLE_UNLIMITED:
|
||||||
case SPOOL_DOWN:
|
case SPOOL_DOWN:
|
||||||
// set motor output based on thrust requests
|
// set motor output based on thrust requests
|
||||||
hal.rcout->cork();
|
|
||||||
rc_write(AP_MOTORS_MOT_1, calc_thrust_to_pwm(_thrust_right));
|
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_2, calc_thrust_to_pwm(_thrust_left));
|
||||||
rc_write(AP_MOTORS_MOT_4, calc_thrust_to_pwm(_thrust_rear));
|
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)));
|
rc_write(AP_MOTORS_CH_TRI_YAW, calc_yaw_radio_output(_pivot_angle, radians(_yaw_servo_angle_max_deg)));
|
||||||
hal.rcout->push();
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user