mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 18:34:19 -04:00
AP_MotorsHeliSingle: move_yaw in -1 to +1 range
This commit is contained in:
parent
f6120b801b
commit
71866be652
@ -436,17 +436,19 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
|
|||||||
}
|
}
|
||||||
|
|
||||||
// move_yaw
|
// move_yaw
|
||||||
void AP_MotorsHeli_Single::move_yaw(int16_t yaw_out)
|
void AP_MotorsHeli_Single::move_yaw(float yaw_out)
|
||||||
{
|
{
|
||||||
_yaw_servo.servo_out = constrain_int16(yaw_out, -4500, 4500);
|
// sanity check yaw_out
|
||||||
|
if (yaw_out < -1.0f) {
|
||||||
if (_yaw_servo.servo_out != yaw_out) {
|
yaw_out = -1.0f;
|
||||||
|
limit.yaw = true;
|
||||||
|
}
|
||||||
|
if (yaw_out > 1.0f) {
|
||||||
|
yaw_out = 1.0f;
|
||||||
limit.yaw = true;
|
limit.yaw = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
_yaw_servo.calc_pwm();
|
rc_write(AP_MOTORS_MOT_4, calc_pwm_output_1to1(yaw_out, _yaw_servo));
|
||||||
|
|
||||||
rc_write(AP_MOTORS_MOT_4, _yaw_servo.radio_out);
|
|
||||||
|
|
||||||
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
|
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
|
||||||
// output gain to exernal gyro
|
// output gain to exernal gyro
|
||||||
@ -457,7 +459,8 @@ void AP_MotorsHeli_Single::move_yaw(int16_t yaw_out)
|
|||||||
}
|
}
|
||||||
} else if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH && _main_rotor.get_desired_speed() > 0) {
|
} else if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH && _main_rotor.get_desired_speed() > 0) {
|
||||||
// output yaw servo to tail rsc
|
// output yaw servo to tail rsc
|
||||||
write_aux(_yaw_servo.servo_out);
|
// To-Do: fix this messy calculation
|
||||||
|
write_aux((yaw_out*0.5f+1.0f) * 1000.0f);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -146,7 +146,7 @@ protected:
|
|||||||
void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out);
|
void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out);
|
||||||
|
|
||||||
// move_yaw - moves the yaw servo
|
// move_yaw - moves the yaw servo
|
||||||
void move_yaw(int16_t yaw_out);
|
void move_yaw(float yaw_out);
|
||||||
|
|
||||||
// write_aux - outputs pwm onto output aux channel (ch7). servo_out parameter is of the range 0 ~ 1000
|
// write_aux - outputs pwm onto output aux channel (ch7). servo_out parameter is of the range 0 ~ 1000
|
||||||
void write_aux(int16_t servo_out);
|
void write_aux(int16_t servo_out);
|
||||||
|
Loading…
Reference in New Issue
Block a user