AP_Motors: added new MOT_PWM_TYPE=8 for PWM range

this allows multirotors to set individual PWM ranges per motor. This
is needed for heliquads flying as multirotors
This commit is contained in:
Andrew Tridgell 2019-10-12 20:28:24 +11:00
parent 8b7b4d6796
commit 4b9311d87d
3 changed files with 28 additions and 5 deletions

View File

@ -78,7 +78,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
// @Param: PWM_TYPE
// @DisplayName: Output PWM type
// @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output
// @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200
// @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200,8:PWMRange
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("PWM_TYPE", 15, AP_MotorsMulticopter, _pwm_type, PWM_TYPE_NORMAL),
@ -512,8 +512,9 @@ void AP_MotorsMulticopter::set_throttle_range(int16_t radio_min, int16_t radio_m
_throttle_radio_min = radio_min;
_throttle_radio_max = radio_max;
// if all outputs are digital adjust the range
if (SRV_Channels::have_digital_outputs(get_motor_mask())) {
// if all outputs are digital adjust the range. We also do this for type PWM_RANGE, as those use the
// scaled output, which is then mapped to PWM via the SRV_Channel library
if (SRV_Channels::have_digital_outputs(get_motor_mask()) || (_pwm_type == PWM_TYPE_PWM_RANGE)) {
_pwm_min = 1000;
_pwm_max = 2000;
}

View File

@ -92,7 +92,12 @@ void AP_Motors::set_radio_passthrough(float roll_input, float pitch_input, float
void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
{
SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(chan);
SRV_Channels::set_output_pwm(function, pwm);
if ((1U<<chan) & _motor_pwm_range_mask) {
// note that PWM_MIN/MAX has been forced to 1000/2000
SRV_Channels::set_output_scaled(function, pwm - 1000);
} else {
SRV_Channels::set_output_pwm(function, pwm);
}
}
/*
@ -142,6 +147,19 @@ void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
case PWM_TYPE_DSHOT1200:
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT1200);
break;
case PWM_TYPE_PWM_RANGE:
/*
this is a motor output type for multirotors which honours
the SERVOn_MIN/MAX values per channel
*/
_motor_pwm_range_mask |= mask;
for (uint8_t i=0; i<16; i++) {
if ((1U<<i) & mask) {
SRV_Channels::set_range(SRV_Channels::get_motor_function(i), 1000);
}
}
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_NORMAL);
break;
default:
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_NORMAL);
break;

View File

@ -220,7 +220,8 @@ public:
PWM_TYPE_DSHOT150 = 4,
PWM_TYPE_DSHOT300 = 5,
PWM_TYPE_DSHOT600 = 6,
PWM_TYPE_DSHOT1200 = 7};
PWM_TYPE_DSHOT1200 = 7,
PWM_TYPE_PWM_RANGE = 8 };
pwm_type get_pwm_type(void) const { return (pwm_type)_pwm_type.get(); }
MAV_TYPE get_frame_mav_type() const { return _mav_type; }
@ -273,6 +274,9 @@ protected:
// mask of what channels need fast output
uint16_t _motor_fast_mask;
// mask of what channels need to use SERVOn_MIN/MAX for output mapping
uint16_t _motor_pwm_range_mask;
// pass through variables
float _roll_radio_passthrough; // roll input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
float _pitch_radio_passthrough; // pitch input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed