mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Motors: rc_map_mask -> motor_mask_to_srv_channel_mask
the naming of this function precedes our rc/srv-channel split
This commit is contained in:
parent
90b8893b4a
commit
8f8283e0f0
@ -107,7 +107,7 @@ uint16_t AP_MotorsCoax::get_motor_mask()
|
||||
1U << AP_MOTORS_MOT_4 |
|
||||
1U << AP_MOTORS_MOT_5 |
|
||||
1U << AP_MOTORS_MOT_6;
|
||||
uint16_t mask = rc_map_mask(motor_mask);
|
||||
uint16_t mask = motor_mask_to_srv_channel_mask(motor_mask);
|
||||
|
||||
// add parent's mask
|
||||
mask |= AP_MotorsMulticopter::get_motor_mask();
|
||||
|
@ -373,7 +373,7 @@ uint16_t AP_MotorsHeli_Single::get_motor_mask()
|
||||
mask |= 1U << AP_MOTORS_HELI_SINGLE_TAILRSC;
|
||||
}
|
||||
|
||||
return rc_map_mask(mask);
|
||||
return motor_mask_to_srv_channel_mask(mask);
|
||||
}
|
||||
|
||||
// update_motor_controls - sends commands to motor controllers
|
||||
|
@ -117,7 +117,7 @@ uint16_t AP_MotorsMatrix::get_motor_mask()
|
||||
motor_mask |= 1U << i;
|
||||
}
|
||||
}
|
||||
uint16_t mask = rc_map_mask(motor_mask);
|
||||
uint16_t mask = motor_mask_to_srv_channel_mask(motor_mask);
|
||||
|
||||
// add parent's mask
|
||||
mask |= AP_MotorsMulticopter::get_motor_mask();
|
||||
|
@ -111,7 +111,7 @@ uint16_t AP_MotorsSingle::get_motor_mask()
|
||||
1U << AP_MOTORS_MOT_5 |
|
||||
1U << AP_MOTORS_MOT_6;
|
||||
|
||||
uint16_t mask = rc_map_mask(motor_mask);
|
||||
uint16_t mask = motor_mask_to_srv_channel_mask(motor_mask);
|
||||
|
||||
// add parent's mask
|
||||
mask |= AP_MotorsMulticopter::get_motor_mask();
|
||||
|
@ -129,7 +129,7 @@ uint16_t AP_MotorsTri::get_motor_mask()
|
||||
(1U << AP_MOTORS_MOT_2) |
|
||||
(1U << AP_MOTORS_MOT_4) |
|
||||
(1U << AP_MOTORS_CH_TRI_YAW);
|
||||
uint16_t mask = rc_map_mask(motor_mask);
|
||||
uint16_t mask = motor_mask_to_srv_channel_mask(motor_mask);
|
||||
|
||||
// add parent's mask
|
||||
mask |= AP_MotorsMulticopter::get_motor_mask();
|
||||
|
@ -102,7 +102,7 @@ void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
|
||||
_motor_fast_mask |= mask;
|
||||
}
|
||||
|
||||
mask = rc_map_mask(mask);
|
||||
mask = motor_mask_to_srv_channel_mask(mask);
|
||||
hal.rcout->set_freq(mask, freq_hz);
|
||||
|
||||
switch (pwm_type(_pwm_type.get())) {
|
||||
@ -142,7 +142,7 @@ void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
|
||||
SERVOn_FUNCTION mappings, and allowing for multiple outputs per
|
||||
motor number
|
||||
*/
|
||||
uint32_t AP_Motors::rc_map_mask(uint32_t mask) const
|
||||
uint32_t AP_Motors::motor_mask_to_srv_channel_mask(uint32_t mask) const
|
||||
{
|
||||
uint32_t mask2 = 0;
|
||||
for (uint8_t i = 0; i < 32; i++) {
|
||||
|
@ -210,7 +210,14 @@ protected:
|
||||
virtual void rc_write(uint8_t chan, uint16_t pwm);
|
||||
virtual void rc_write_angle(uint8_t chan, int16_t angle_cd);
|
||||
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz);
|
||||
virtual uint32_t rc_map_mask(uint32_t mask) const;
|
||||
|
||||
|
||||
/*
|
||||
map an internal motor mask to real motor mask, accounting for
|
||||
SERVOn_FUNCTION mappings, and allowing for multiple outputs per
|
||||
motor number
|
||||
*/
|
||||
uint32_t motor_mask_to_srv_channel_mask(uint32_t mask) const;
|
||||
|
||||
// add a motor to the motor map
|
||||
void add_motor_num(int8_t motor_num);
|
||||
|
Loading…
Reference in New Issue
Block a user