mirror of https://github.com/ArduPilot/ardupilot
TradHeli: ext gyro gain range 0 to 1000
This commit is contained in:
parent
197fc67897
commit
bc4dba0eea
|
@ -117,7 +117,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
||||||
// @Param: GYR_GAIN
|
// @Param: GYR_GAIN
|
||||||
// @DisplayName: External Gyro Gain
|
// @DisplayName: External Gyro Gain
|
||||||
// @Description: PWM sent to external gyro on ch7 when tail type is Servo w/ ExtGyro
|
// @Description: PWM sent to external gyro on ch7 when tail type is Servo w/ ExtGyro
|
||||||
// @Range: 1000 2000
|
// @Range: 0 1000
|
||||||
// @Units: PWM
|
// @Units: PWM
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
@ -317,7 +317,7 @@ void AP_MotorsHeli::output_test()
|
||||||
|
|
||||||
// external gyro
|
// external gyro
|
||||||
if (_tail_type == AP_MOTORS_HELI_TAILTYPE_SERVO_EXTGYRO) {
|
if (_tail_type == AP_MOTORS_HELI_TAILTYPE_SERVO_EXTGYRO) {
|
||||||
hal.rcout->write(AP_MOTORS_HELI_AUX, _ext_gyro_gain);
|
write_aux(_ext_gyro_gain);
|
||||||
}
|
}
|
||||||
|
|
||||||
// servo 4
|
// servo 4
|
||||||
|
@ -650,7 +650,7 @@ void AP_MotorsHeli::move_swash(int16_t roll_out, int16_t pitch_out, int16_t coll
|
||||||
|
|
||||||
// output gain to exernal gyro
|
// output gain to exernal gyro
|
||||||
if (_tail_type == AP_MOTORS_HELI_TAILTYPE_SERVO_EXTGYRO) {
|
if (_tail_type == AP_MOTORS_HELI_TAILTYPE_SERVO_EXTGYRO) {
|
||||||
hal.rcout->write(AP_MOTORS_HELI_AUX, _ext_gyro_gain);
|
write_aux(_ext_gyro_gain);
|
||||||
}
|
}
|
||||||
|
|
||||||
// to be compatible with other frame types
|
// to be compatible with other frame types
|
||||||
|
|
|
@ -58,7 +58,7 @@
|
||||||
#define AP_MOTORS_HELI_TAILTYPE_DIRECTDRIVE_FIXEDPITCH 3
|
#define AP_MOTORS_HELI_TAILTYPE_DIRECTDRIVE_FIXEDPITCH 3
|
||||||
|
|
||||||
// default external gyro gain (ch7 out)
|
// default external gyro gain (ch7 out)
|
||||||
#define AP_MOTORS_HELI_EXT_GYRO_GAIN 1350
|
#define AP_MOTORS_HELI_EXT_GYRO_GAIN 350
|
||||||
|
|
||||||
// minimum outputs for direct drive motors
|
// minimum outputs for direct drive motors
|
||||||
#define AP_MOTOR_HELI_DIRECTDRIVE_DEFAULT 500
|
#define AP_MOTOR_HELI_DIRECTDRIVE_DEFAULT 500
|
||||||
|
|
Loading…
Reference in New Issue