AP_Motors: Heli: get_output_mask return only motors

This commit is contained in:
Iampete1 2023-05-05 20:06:42 +01:00 committed by Bill Geyer
parent e492f49470
commit 81f3d3edda
9 changed files with 21 additions and 55 deletions

View File

@ -617,3 +617,10 @@ bool AP_MotorsHeli::arming_checks(size_t buflen, char *buffer) const
return true;
}
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint32_t AP_MotorsHeli::get_motor_mask()
{
return _main_rotor.get_output_mask();
}

View File

@ -113,7 +113,7 @@ public:
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
virtual uint32_t get_motor_mask() override = 0;
virtual uint32_t get_motor_mask() override;
virtual void set_acro_tail(bool set) {}

View File

@ -463,25 +463,6 @@ float AP_MotorsHeli_Dual::get_swashplate (int8_t swash_num, int8_t swash_axis, f
return swash_tilt;
}
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint32_t AP_MotorsHeli_Dual::get_motor_mask()
{
// dual heli uses channels 1,2,3,4,5,6 and 8
uint32_t mask = 0;
for (uint8_t i=0; i<AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS; i++) {
mask |= 1U << (AP_MOTORS_MOT_1+i);
}
if (_swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
mask |= 1U << AP_MOTORS_MOT_7;
}
if (_swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
mask |= 1U << AP_MOTORS_MOT_8;
}
mask |= 1U << AP_MOTORS_HELI_RSC;
return mask;
}
// update_motor_controls - sends commands to motor controllers
void AP_MotorsHeli_Dual::update_motor_control(RotorControlState state)
{

View File

@ -76,9 +76,6 @@ public:
// calculate_armed_scalars - recalculates scalars that can change while armed
void calculate_armed_scalars() override;
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
uint32_t get_motor_mask() override;
// has_flybar - returns true if we have a mechical flybar
bool has_flybar() const override { return AP_MOTORS_HELI_NOFLYBAR; }

View File

@ -173,18 +173,6 @@ void AP_MotorsHeli_Quad::calculate_roll_pitch_collective_factors()
}
}
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint32_t AP_MotorsHeli_Quad::get_motor_mask()
{
uint32_t mask = 0;
for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
mask |= 1U << (AP_MOTORS_MOT_1+i);
}
mask |= 1U << AP_MOTORS_HELI_RSC;
return mask;
}
// update_motor_controls - sends commands to motor controllers
void AP_MotorsHeli_Quad::update_motor_control(RotorControlState state)
{

View File

@ -55,9 +55,6 @@ public:
// calculate_armed_scalars - recalculates scalars that can change while armed
void calculate_armed_scalars() override;
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
uint32_t get_motor_mask() override;
// has_flybar - returns true if we have a mechanical flybar
bool has_flybar() const override { return AP_MOTORS_HELI_NOFLYBAR; }

View File

@ -510,6 +510,15 @@ void AP_MotorsHeli_RSC::write_rsc(float servo_out)
}
}
// Return mask of output channels which the RSC is outputting on
uint32_t AP_MotorsHeli_RSC::get_output_mask() const
{
if (_control_mode == ROTOR_CONTROL_MODE_DISABLED) {
return 0;
}
return SRV_Channels::get_output_channel_mask(_aux_fn);
}
// calculate_throttlecurve - uses throttle curve and collective input to determine throttle setting
float AP_MotorsHeli_RSC::calculate_throttlecurve(float collective_in)
{

View File

@ -125,6 +125,9 @@ public:
// output - update value to send to ESC/Servo
void output(RotorControlState state);
// Return mask of output channels which the RSC is outputting on
uint32_t get_output_mask() const;
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];

View File

@ -350,23 +350,7 @@ void AP_MotorsHeli_Single::calculate_scalars()
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint32_t AP_MotorsHeli_Single::get_motor_mask()
{
// heli uses channels 1,2,3,4 and 8
// setup fast channels
uint32_t mask = 1U << 0 | 1U << 1 | 1U << 2 | 1U << 3 | 1U << AP_MOTORS_HELI_RSC;
if (_swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
mask |= 1U << 4;
}
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
mask |= 1U << AP_MOTORS_HELI_SINGLE_EXTGYRO;
}
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) {
mask |= 1U << AP_MOTORS_HELI_SINGLE_TAILRSC;
}
return motor_mask_to_srv_channel_mask(mask);
return _main_rotor.get_output_mask() | _tail_rotor.get_output_mask();
}
// update_motor_controls - sends commands to motor controllers