mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Motors: allow enabling oneshot on a subset of motors
This commit is contained in:
parent
bcd0d48ced
commit
fd7c87e629
@ -79,7 +79,7 @@ void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
|
|||||||
// we have a mapped motor number for this channel
|
// we have a mapped motor number for this channel
|
||||||
chan = _motor_map[chan];
|
chan = _motor_map[chan];
|
||||||
}
|
}
|
||||||
if (_pwm_type == PWM_TYPE_ONESHOT125) {
|
if (_pwm_type == PWM_TYPE_ONESHOT125 && (_motor_fast_mask & (1U<<chan))) {
|
||||||
// OneShot125 uses a PWM range from 125 to 250 usec
|
// OneShot125 uses a PWM range from 125 to 250 usec
|
||||||
pwm /= 8;
|
pwm /= 8;
|
||||||
/*
|
/*
|
||||||
@ -101,9 +101,14 @@ void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
|
|||||||
*/
|
*/
|
||||||
void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
|
void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
|
||||||
{
|
{
|
||||||
hal.rcout->set_freq(rc_map_mask(mask), freq_hz);
|
mask = rc_map_mask(mask);
|
||||||
if (_pwm_type == PWM_TYPE_ONESHOT ||
|
if (freq_hz > 50) {
|
||||||
_pwm_type == PWM_TYPE_ONESHOT125) {
|
_motor_fast_mask |= mask;
|
||||||
|
}
|
||||||
|
hal.rcout->set_freq(mask, freq_hz);
|
||||||
|
if ((_pwm_type == PWM_TYPE_ONESHOT ||
|
||||||
|
_pwm_type == PWM_TYPE_ONESHOT125) &&
|
||||||
|
freq_hz > 50) {
|
||||||
// tell HAL to do immediate output
|
// tell HAL to do immediate output
|
||||||
hal.rcout->set_output_mode(AP_HAL::RCOutput::MODE_PWM_ONESHOT);
|
hal.rcout->set_output_mode(AP_HAL::RCOutput::MODE_PWM_ONESHOT);
|
||||||
}
|
}
|
||||||
|
@ -176,6 +176,7 @@ protected:
|
|||||||
// mapping to output channels
|
// mapping to output channels
|
||||||
uint8_t _motor_map[AP_MOTORS_MAX_NUM_MOTORS];
|
uint8_t _motor_map[AP_MOTORS_MAX_NUM_MOTORS];
|
||||||
uint16_t _motor_map_mask;
|
uint16_t _motor_map_mask;
|
||||||
|
uint16_t _motor_fast_mask;
|
||||||
|
|
||||||
// pass through variables
|
// pass through variables
|
||||||
float _roll_radio_passthrough = 0.0f; // roll input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
|
float _roll_radio_passthrough = 0.0f; // roll input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
|
||||||
|
Loading…
Reference in New Issue
Block a user