mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-05 13:14:03 -04:00
AP_MotorsHeli: Semantic change. Motor Runup to Rotor Runup
This commit is contained in:
parent
db3852522f
commit
d24664ccf9
@ -355,14 +355,14 @@ void AP_MotorsHeli::set_desired_rotor_speed(int16_t desired_speed)
|
||||
}
|
||||
|
||||
// return true if the main rotor is up to speed
|
||||
bool AP_MotorsHeli::motor_runup_complete() const
|
||||
bool AP_MotorsHeli::rotor_runup_complete() const
|
||||
{
|
||||
// if we have no control of motors, assume pilot has spun them up
|
||||
if (_rsc_mode == AP_MOTORS_HELI_RSC_MODE_NONE) {
|
||||
return true;
|
||||
}
|
||||
|
||||
return _heliflags.motor_runup_complete;
|
||||
return _heliflags.rotor_runup_complete;
|
||||
}
|
||||
|
||||
// recalc_scalers - recalculates various scalers used. Should be called at about 1hz to allow users to see effect of changing parameters
|
||||
@ -759,11 +759,11 @@ void AP_MotorsHeli::rotor_ramp(int16_t rotor_target)
|
||||
}
|
||||
|
||||
// set runup complete flag
|
||||
if (!_heliflags.motor_runup_complete && rotor_target > 0 && _rotor_speed_estimate >= rotor_target) {
|
||||
_heliflags.motor_runup_complete = true;
|
||||
if (!_heliflags.rotor_runup_complete && rotor_target > 0 && _rotor_speed_estimate >= rotor_target) {
|
||||
_heliflags.rotor_runup_complete = true;
|
||||
}
|
||||
if (_heliflags.motor_runup_complete && rotor_target == 0 && _rotor_speed_estimate <= 0) {
|
||||
_heliflags.motor_runup_complete = false;
|
||||
if (_heliflags.rotor_runup_complete && rotor_target == 0 && _rotor_speed_estimate <= 0) {
|
||||
_heliflags.rotor_runup_complete = false;
|
||||
}
|
||||
|
||||
// output to rsc servo
|
||||
|
@ -75,9 +75,6 @@
|
||||
#define AP_MOTORS_HELI_RSC_RUNUP_TIME 10 // 10 seconds for rotor to reach full speed
|
||||
#define AP_MOTORS_HELI_TAIL_RAMP_INCREMENT 5 // 5 is 2 seconds for direct drive tail rotor to reach to full speed (5 = (2sec*100hz)/1000)
|
||||
|
||||
// motor run-up time default in 100th of seconds
|
||||
#define AP_MOTORS_HELI_MOTOR_RUNUP_TIME 500 // 500 = 5 seconds
|
||||
|
||||
// flybar types
|
||||
#define AP_MOTORS_HELI_NOFLYBAR 0
|
||||
#define AP_MOTORS_HELI_FLYBAR 1
|
||||
@ -123,7 +120,7 @@ public:
|
||||
// initialise flags
|
||||
_heliflags.swash_initialised = 0;
|
||||
_heliflags.landing_collective = 0;
|
||||
_heliflags.motor_runup_complete = 0;
|
||||
_heliflags.rotor_runup_complete = 0;
|
||||
};
|
||||
|
||||
// init
|
||||
@ -180,7 +177,7 @@ public:
|
||||
void set_desired_rotor_speed(int16_t desired_speed);
|
||||
|
||||
// return true if the main rotor is up to speed
|
||||
bool motor_runup_complete() const;
|
||||
bool rotor_runup_complete() const;
|
||||
|
||||
// recalc_scalers - recalculates various scalers used. Should be called at about 1hz to allow users to see effect of changing parameters
|
||||
void recalc_scalers();
|
||||
@ -264,7 +261,7 @@ private:
|
||||
struct heliflags_type {
|
||||
uint8_t swash_initialised : 1; // true if swash has been initialised
|
||||
uint8_t landing_collective : 1; // true if collective is setup for landing which has much higher minimum
|
||||
uint8_t motor_runup_complete : 1; // true if the rotors have had enough time to wind up
|
||||
uint8_t rotor_runup_complete : 1; // true if the rotors have had enough time to wind up
|
||||
} _heliflags;
|
||||
|
||||
// parameters
|
||||
|
Loading…
Reference in New Issue
Block a user