AP_Motors: added oneshot support via MOT_PWM_MODE

MOT_PWM_MODE=0 is normal
MOT_PWM_MODE=1 is oneshot
MOT_PWM_MODE=2 is oneshot125
This commit is contained in:
Andrew Tridgell 2016-04-13 16:33:20 +10:00
parent 934b4dd475
commit f54bcc6c7f
3 changed files with 19 additions and 0 deletions

View File

@ -98,6 +98,13 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
// @User: Advanced
AP_GROUPINFO("THR_MIX_MAX", 14, AP_MotorsMulticopter, _thr_mix_max, AP_MOTORS_THR_MIX_MAX_DEFAULT),
// @Param: PWM_MODE
// @DisplayName: Output PWM mode
// @Description: This selects the output PWM mode, allowing for normal PWM continuous output or OneShot125
// @Values: 0:Normal,1:OneShot,2:OneShot125
// @User: Advanced
AP_GROUPINFO("PWM_MODE", 15, AP_MotorsMulticopter, _pwm_mode, PWM_MODE_NORMAL),
AP_GROUPEND
};

View File

@ -79,6 +79,10 @@ void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
// we have a mapped motor number for this channel
chan = _motor_map[chan];
}
if (_pwm_mode == PWM_MODE_ONESHOT125) {
// OneShot125 uses a PWM range from 125 to 250 usec
pwm /= 8;
}
hal.rcout->write(chan, pwm);
}
@ -88,6 +92,11 @@ void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
{
hal.rcout->set_freq(rc_map_mask(mask), freq_hz);
if (_pwm_mode == PWM_MODE_ONESHOT ||
_pwm_mode == PWM_MODE_ONESHOT125) {
// tell HAL to do immediate output
hal.rcout->set_output_mode(AP_HAL::RCOutput::MODE_PWM_ONESHOT);
}
}
void AP_Motors::rc_enable_ch(uint8_t chan)

View File

@ -179,4 +179,7 @@ protected:
float _pitch_radio_passthrough = 0.0f; // pitch input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
float _throttle_radio_passthrough = 0.0f; // throttle/collective input from pilot in 0 ~ 1 range. used for setup and providing servo feedback while landed
float _yaw_radio_passthrough = 0.0f; // yaw input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
enum pwm_mode { PWM_MODE_NORMAL=0, PWM_MODE_ONESHOT=1, PWM_MODE_ONESHOT125=2 };
AP_Int8 _pwm_mode; // PWM output mode
};