mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
TradHeli: Minor change to two param defaults
Also one param name in the code clarified.
This commit is contained in:
parent
8b36c59d8b
commit
d441354961
@ -204,7 +204,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("TAIL_SPEED", 24, AP_MotorsHeli, _direct_drive_tailspeed, AP_MOTOR_HELI_DIRECTDRIVE_DEFAULT),
|
||||
AP_GROUPINFO("TAIL_SPEED", 24, AP_MotorsHeli, _direct_drive_tailspeed, AP_MOTOR_HELI_DDTAIL_DEFAULT),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
@ -38,8 +38,8 @@
|
||||
#define AP_MOTORS_HELI_SWASH_H1 1
|
||||
|
||||
// default swash min and max angles and positions
|
||||
#define AP_MOTORS_HELI_SWASH_ROLL_MAX 4500
|
||||
#define AP_MOTORS_HELI_SWASH_PITCH_MAX 4500
|
||||
#define AP_MOTORS_HELI_SWASH_ROLL_MAX 2500
|
||||
#define AP_MOTORS_HELI_SWASH_PITCH_MAX 2500
|
||||
#define AP_MOTORS_HELI_COLLECTIVE_MIN 1250
|
||||
#define AP_MOTORS_HELI_COLLECTIVE_MAX 1750
|
||||
#define AP_MOTORS_HELI_COLLECTIVE_MID 1500
|
||||
@ -61,7 +61,7 @@
|
||||
#define AP_MOTORS_HELI_EXT_GYRO_GAIN 350
|
||||
|
||||
// minimum outputs for direct drive motors
|
||||
#define AP_MOTOR_HELI_DIRECTDRIVE_DEFAULT 500
|
||||
#define AP_MOTOR_HELI_DDTAIL_DEFAULT 500
|
||||
|
||||
|
||||
// main rotor speed control types (ch8 out)
|
||||
|
Loading…
Reference in New Issue
Block a user