mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Motors: eliminate flags structure
Saves about 44 bytes
This commit is contained in:
parent
798c3fd0b7
commit
41ab59dcdb
@ -38,13 +38,13 @@ void AP_MotorsCoax::init(motor_frame_class frame_class, motor_frame_type frame_t
|
||||
}
|
||||
|
||||
// record successful initialisation if what we setup was the desired frame_class
|
||||
_flags.initialised_ok = (frame_class == MOTOR_FRAME_COAX);
|
||||
set_initialised_ok(frame_class == MOTOR_FRAME_COAX);
|
||||
}
|
||||
|
||||
// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
|
||||
void AP_MotorsCoax::set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
|
||||
{
|
||||
_flags.initialised_ok = (frame_class == MOTOR_FRAME_COAX);
|
||||
set_initialised_ok(frame_class == MOTOR_FRAME_COAX);
|
||||
}
|
||||
|
||||
// set update rate to motors - a value in hertz
|
||||
|
@ -132,7 +132,7 @@ void AP_MotorsHeli::init(motor_frame_class frame_class, motor_frame_type frame_t
|
||||
calculate_scalars();
|
||||
|
||||
// record successful initialisation if what we setup was the desired frame_class
|
||||
_flags.initialised_ok = (frame_class == MOTOR_FRAME_HELI);
|
||||
set_initialised_ok(frame_class == MOTOR_FRAME_HELI);
|
||||
|
||||
// set flag to true so targets are initialized once aircraft is armed for first time
|
||||
_heliflags.init_targets_on_arming = true;
|
||||
@ -142,7 +142,7 @@ void AP_MotorsHeli::init(motor_frame_class frame_class, motor_frame_type frame_t
|
||||
// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
|
||||
void AP_MotorsHeli::set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
|
||||
{
|
||||
_flags.initialised_ok = (frame_class == MOTOR_FRAME_HELI);
|
||||
set_initialised_ok(frame_class == MOTOR_FRAME_HELI);
|
||||
}
|
||||
|
||||
// output_min - sets servos to neutral point with motors stopped
|
||||
@ -170,12 +170,11 @@ void AP_MotorsHeli::output()
|
||||
// run spool logic
|
||||
output_logic();
|
||||
|
||||
if (_flags.armed) {
|
||||
if (armed()) {
|
||||
// block servo_test from happening at disarm
|
||||
_servo_test_cycle_counter = 0;
|
||||
|
||||
calculate_armed_scalars();
|
||||
if (!_flags.interlock) {
|
||||
if (!get_interlock()) {
|
||||
output_armed_zero_throttle();
|
||||
} else {
|
||||
output_armed_stabilizing();
|
||||
@ -285,8 +284,8 @@ void AP_MotorsHeli::output_disarmed()
|
||||
void AP_MotorsHeli::output_logic()
|
||||
{
|
||||
// force desired and current spool mode if disarmed and armed with interlock enabled
|
||||
if (_flags.armed) {
|
||||
if (!_flags.interlock) {
|
||||
if (armed()) {
|
||||
if (!get_interlock()) {
|
||||
_spool_desired = DesiredSpoolState::GROUND_IDLE;
|
||||
} else {
|
||||
_heliflags.init_targets_on_arming = false;
|
||||
|
@ -223,7 +223,7 @@ void AP_MotorsHeli_Dual::set_update_rate( uint16_t speed_hz )
|
||||
// init_outputs
|
||||
bool AP_MotorsHeli_Dual::init_outputs()
|
||||
{
|
||||
if (!_flags.initialised_ok) {
|
||||
if (!initialised_ok()) {
|
||||
// make sure 6 output channels are mapped
|
||||
for (uint8_t i=0; i<AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS; i++) {
|
||||
add_motor_num(CH_1+i);
|
||||
@ -258,7 +258,7 @@ bool AP_MotorsHeli_Dual::init_outputs()
|
||||
reset_swash_servo(SRV_Channels::get_motor_function(7));
|
||||
}
|
||||
|
||||
_flags.initialised_ok = true;
|
||||
set_initialised_ok(true);
|
||||
|
||||
return true;
|
||||
}
|
||||
@ -335,7 +335,7 @@ void AP_MotorsHeli_Dual::calculate_armed_scalars()
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "RSC control mode change failed");
|
||||
}
|
||||
// saves rsc mode parameter when disarmed if it had been reset while armed
|
||||
if (_heliflags.save_rsc_mode && !_flags.armed) {
|
||||
if (_heliflags.save_rsc_mode && !armed()) {
|
||||
_main_rotor._rsc_mode.save();
|
||||
_heliflags.save_rsc_mode = false;
|
||||
}
|
||||
@ -606,7 +606,7 @@ void AP_MotorsHeli_Dual::move_actuators(float roll_out, float pitch_out, float c
|
||||
|
||||
void AP_MotorsHeli_Dual::output_to_motors()
|
||||
{
|
||||
if (!_flags.initialised_ok) {
|
||||
if (!initialised_ok()) {
|
||||
return;
|
||||
}
|
||||
// actually move the servos. PWM is sent based on nominal 1500 center. servo output shifts center based on trim value.
|
||||
|
@ -48,7 +48,7 @@ void AP_MotorsHeli_Quad::set_update_rate( uint16_t speed_hz )
|
||||
// init_outputs
|
||||
bool AP_MotorsHeli_Quad::init_outputs()
|
||||
{
|
||||
if (_flags.initialised_ok) {
|
||||
if (initialised_ok()) {
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -67,7 +67,7 @@ bool AP_MotorsHeli_Quad::init_outputs()
|
||||
_main_rotor.set_ext_gov_arot_bail(0);
|
||||
}
|
||||
|
||||
_flags.initialised_ok = true;
|
||||
set_initialised_ok(true);
|
||||
|
||||
return true;
|
||||
}
|
||||
@ -123,7 +123,7 @@ void AP_MotorsHeli_Quad::calculate_armed_scalars()
|
||||
_heliflags.save_rsc_mode = true;
|
||||
}
|
||||
// saves rsc mode parameter when disarmed if it had been reset while armed
|
||||
if (_heliflags.save_rsc_mode && !_flags.armed) {
|
||||
if (_heliflags.save_rsc_mode && !armed()) {
|
||||
_main_rotor._rsc_mode.save();
|
||||
_heliflags.save_rsc_mode = false;
|
||||
}
|
||||
@ -305,7 +305,7 @@ void AP_MotorsHeli_Quad::move_actuators(float roll_out, float pitch_out, float c
|
||||
|
||||
void AP_MotorsHeli_Quad::output_to_motors()
|
||||
{
|
||||
if (!_flags.initialised_ok) {
|
||||
if (!initialised_ok()) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -161,7 +161,7 @@ void AP_MotorsHeli_Single::set_update_rate( uint16_t speed_hz )
|
||||
// init_outputs - initialise Servo/PWM ranges and endpoints
|
||||
bool AP_MotorsHeli_Single::init_outputs()
|
||||
{
|
||||
if (!_flags.initialised_ok) {
|
||||
if (!initialised_ok()) {
|
||||
// map primary swash servos
|
||||
for (uint8_t i=0; i<AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS; i++) {
|
||||
add_motor_num(CH_1+i);
|
||||
@ -215,7 +215,7 @@ bool AP_MotorsHeli_Single::init_outputs()
|
||||
// yaw servo is an angle from -4500 to 4500
|
||||
SRV_Channels::set_angle(SRV_Channel::k_motor4, YAW_SERVO_MAX_ANGLE);
|
||||
|
||||
_flags.initialised_ok = true;
|
||||
set_initialised_ok(true);
|
||||
|
||||
return true;
|
||||
}
|
||||
@ -294,7 +294,7 @@ void AP_MotorsHeli_Single::calculate_armed_scalars()
|
||||
_heliflags.save_rsc_mode = true;
|
||||
}
|
||||
// saves rsc mode parameter when disarmed if it had been reset while armed
|
||||
if (_heliflags.save_rsc_mode && !_flags.armed) {
|
||||
if (_heliflags.save_rsc_mode && !armed()) {
|
||||
_main_rotor._rsc_mode.save();
|
||||
_heliflags.save_rsc_mode = false;
|
||||
}
|
||||
@ -503,7 +503,7 @@ void AP_MotorsHeli_Single::move_yaw(float yaw_out)
|
||||
|
||||
void AP_MotorsHeli_Single::output_to_motors()
|
||||
{
|
||||
if (!_flags.initialised_ok) {
|
||||
if (!initialised_ok()) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -883,7 +883,7 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
// normalise factors to magnitude 0.5
|
||||
normalise_rpy_factors();
|
||||
|
||||
_flags.initialised_ok = success;
|
||||
set_initialised_ok(success);
|
||||
}
|
||||
|
||||
// normalizes the roll, pitch and yaw factors so maximum magnitude is 0.5
|
||||
|
@ -307,7 +307,7 @@ float AP_MotorsMulticopter::get_current_limit_max_throttle()
|
||||
float _batt_current;
|
||||
|
||||
if (_batt_current_max <= 0 || // return maximum if current limiting is disabled
|
||||
!_flags.armed || // remove throttle limit if disarmed
|
||||
!armed() || // remove throttle limit if disarmed
|
||||
!battery.current_amps(_batt_current, _batt_idx)) { // no current monitoring is available
|
||||
_throttle_limit = 1.0f;
|
||||
return 1.0f;
|
||||
@ -533,7 +533,7 @@ void AP_MotorsMulticopter::update_throttle_hover(float dt)
|
||||
// run spool logic
|
||||
void AP_MotorsMulticopter::output_logic()
|
||||
{
|
||||
if (_flags.armed) {
|
||||
if (armed()) {
|
||||
if (_disarm_disable_pwm && (_disarm_safe_timer < _safe_time)) {
|
||||
_disarm_safe_timer += 1.0f/_loop_rate;
|
||||
} else {
|
||||
@ -544,7 +544,7 @@ void AP_MotorsMulticopter::output_logic()
|
||||
}
|
||||
|
||||
// force desired and current spool mode if disarmed or not interlocked
|
||||
if (!_flags.armed || !_flags.interlock) {
|
||||
if (!armed() || !get_interlock()) {
|
||||
_spool_desired = DesiredSpoolState::SHUT_DOWN;
|
||||
_spool_state = SpoolState::SHUT_DOWN;
|
||||
}
|
||||
|
@ -38,7 +38,7 @@ void AP_MotorsSingle::init(motor_frame_class frame_class, motor_frame_type frame
|
||||
}
|
||||
|
||||
// record successful initialisation if what we setup was the desired frame_class
|
||||
_flags.initialised_ok = (frame_class == MOTOR_FRAME_SINGLE);
|
||||
set_initialised_ok(frame_class == MOTOR_FRAME_SINGLE);
|
||||
}
|
||||
|
||||
// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
|
||||
@ -61,7 +61,7 @@ void AP_MotorsSingle::set_update_rate(uint16_t speed_hz)
|
||||
|
||||
void AP_MotorsSingle::output_to_motors()
|
||||
{
|
||||
if (!_flags.initialised_ok) {
|
||||
if (!initialised_ok()) {
|
||||
return;
|
||||
}
|
||||
switch (_spool_state) {
|
||||
|
@ -54,7 +54,7 @@ void AP_MotorsTailsitter::init(motor_frame_class frame_class, motor_frame_type f
|
||||
SRV_Channels::set_angle(SRV_Channel::k_tiltMotorLeft, SERVO_OUTPUT_RANGE);
|
||||
|
||||
// record successful initialisation if what we setup was the desired frame_class
|
||||
_flags.initialised_ok = (frame_class == MOTOR_FRAME_TAILSITTER);
|
||||
set_initialised_ok(frame_class == MOTOR_FRAME_TAILSITTER);
|
||||
}
|
||||
|
||||
|
||||
@ -78,7 +78,7 @@ void AP_MotorsTailsitter::set_update_rate(uint16_t speed_hz)
|
||||
|
||||
void AP_MotorsTailsitter::output_to_motors()
|
||||
{
|
||||
if (!_flags.initialised_ok) {
|
||||
if (!initialised_ok()) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -55,7 +55,7 @@ void AP_MotorsTri::init(motor_frame_class frame_class, motor_frame_type frame_ty
|
||||
}
|
||||
|
||||
// record successful initialisation if what we setup was the desired frame_class
|
||||
_flags.initialised_ok = (frame_class == MOTOR_FRAME_TRI);
|
||||
set_initialised_ok(frame_class == MOTOR_FRAME_TRI);
|
||||
}
|
||||
|
||||
// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
|
||||
@ -68,7 +68,7 @@ void AP_MotorsTri::set_frame_class_and_type(motor_frame_class frame_class, motor
|
||||
_pitch_reversed = false;
|
||||
}
|
||||
|
||||
_flags.initialised_ok = (frame_class == MOTOR_FRAME_TRI) && SRV_Channels::function_assigned(SRV_Channel::k_motor7);
|
||||
set_initialised_ok((frame_class == MOTOR_FRAME_TRI) && SRV_Channels::function_assigned(SRV_Channel::k_motor7));
|
||||
}
|
||||
|
||||
// set update rate to motors - a value in hertz
|
||||
|
@ -50,8 +50,8 @@ AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
|
||||
|
||||
void AP_Motors::armed(bool arm)
|
||||
{
|
||||
if (_flags.armed != arm) {
|
||||
_flags.armed = arm;
|
||||
if (_armed != arm) {
|
||||
_armed = arm;
|
||||
AP_Notify::flags.armed = arm;
|
||||
if (!arm) {
|
||||
save_params_on_disarm();
|
||||
@ -61,7 +61,7 @@ void AP_Motors::armed(bool arm)
|
||||
|
||||
void AP_Motors::set_desired_spool_state(DesiredSpoolState spool)
|
||||
{
|
||||
if (_flags.armed || (spool == DesiredSpoolState::SHUT_DOWN)) {
|
||||
if (_armed || (spool == DesiredSpoolState::SHUT_DOWN)) {
|
||||
_spool_desired = spool;
|
||||
}
|
||||
};
|
||||
|
@ -71,17 +71,18 @@ public:
|
||||
static AP_Motors *get_singleton(void) { return _singleton; }
|
||||
|
||||
// check initialisation succeeded
|
||||
bool initialised_ok() const { return _flags.initialised_ok; }
|
||||
bool initialised_ok() const { return _initialised_ok; }
|
||||
void set_initialised_ok(bool val) { _initialised_ok = val; }
|
||||
|
||||
// arm, disarm or check status status of motors
|
||||
bool armed() const { return _flags.armed; }
|
||||
bool armed() const { return _armed; }
|
||||
void armed(bool arm);
|
||||
|
||||
// set motor interlock status
|
||||
void set_interlock(bool set) { _flags.interlock = set;}
|
||||
void set_interlock(bool set) { _interlock = set;}
|
||||
|
||||
// get motor interlock status. true means motors run, false motors don't run
|
||||
bool get_interlock() const { return _flags.interlock; }
|
||||
bool get_interlock() const { return _interlock; }
|
||||
|
||||
// set_roll, set_pitch, set_yaw, set_throttle
|
||||
void set_roll(float roll_in) { _roll_in = roll_in; }; // range -1 ~ +1
|
||||
@ -198,7 +199,7 @@ public:
|
||||
PWM_TYPE_DSHOT600 = 6,
|
||||
PWM_TYPE_DSHOT1200 = 7};
|
||||
pwm_type get_pwm_type(void) const { return (pwm_type)_pwm_type.get(); }
|
||||
|
||||
|
||||
protected:
|
||||
// output functions that should be overloaded by child classes
|
||||
virtual void output_armed_stabilizing() = 0;
|
||||
@ -216,13 +217,6 @@ protected:
|
||||
// save parameters as part of disarming
|
||||
virtual void save_params_on_disarm() {}
|
||||
|
||||
// flag bitmask
|
||||
struct AP_Motors_flags {
|
||||
uint8_t armed : 1; // 0 if disarmed, 1 if armed
|
||||
uint8_t interlock : 1; // 1 if the motor interlock is enabled (i.e. motors run), 0 if disabled (motors don't run)
|
||||
uint8_t initialised_ok : 1; // 1 if initialisation was successful
|
||||
} _flags;
|
||||
|
||||
// internal variables
|
||||
uint16_t _loop_rate; // rate in Hz at which output() function is called (normally 400hz)
|
||||
uint16_t _speed_hz; // speed in hz to send updates to motors
|
||||
@ -261,7 +255,13 @@ protected:
|
||||
float _thrust_boost_ratio; // choice between highest and second highest motor output for output mixing (0 ~ 1). Zero is normal operation
|
||||
|
||||
private:
|
||||
|
||||
bool _armed; // 0 if disarmed, 1 if armed
|
||||
bool _interlock; // 1 if the motor interlock is enabled (i.e. motors run), 0 if disabled (motors don't run)
|
||||
bool _initialised_ok; // 1 if initialisation was successful
|
||||
|
||||
static AP_Motors *_singleton;
|
||||
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
|
Loading…
Reference in New Issue
Block a user