mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 11:08:29 -04:00
AP_IOMCU: implement manual_rc_mask
This commit is contained in:
parent
27f06ce810
commit
beff16abe6
@ -788,7 +788,8 @@ void AP_IOMCU::shutdown(void)
|
|||||||
setup for mixing. This allows fixed wing aircraft to fly in manual
|
setup for mixing. This allows fixed wing aircraft to fly in manual
|
||||||
mode if the FMU dies
|
mode if the FMU dies
|
||||||
*/
|
*/
|
||||||
bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan, float mixing_gain)
|
bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan,
|
||||||
|
float mixing_gain, uint16_t manual_rc_mask)
|
||||||
{
|
{
|
||||||
if (config.protocol_version != IOMCU_PROTOCOL_VERSION) {
|
if (config.protocol_version != IOMCU_PROTOCOL_VERSION) {
|
||||||
return false;
|
return false;
|
||||||
@ -833,6 +834,7 @@ bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan, float mixing_
|
|||||||
|
|
||||||
MIX_UPDATE(mixing.rc_chan_override, override_chan);
|
MIX_UPDATE(mixing.rc_chan_override, override_chan);
|
||||||
MIX_UPDATE(mixing.mixing_gain, (uint16_t)(mixing_gain*1000));
|
MIX_UPDATE(mixing.mixing_gain, (uint16_t)(mixing_gain*1000));
|
||||||
|
MIX_UPDATE(mixing.manual_rc_mask, manual_rc_mask);
|
||||||
|
|
||||||
// and enable
|
// and enable
|
||||||
MIX_UPDATE(mixing.enabled, 1);
|
MIX_UPDATE(mixing.enabled, 1);
|
||||||
|
@ -91,7 +91,8 @@ public:
|
|||||||
void shutdown();
|
void shutdown();
|
||||||
|
|
||||||
// setup for FMU failsafe mixing
|
// setup for FMU failsafe mixing
|
||||||
bool setup_mixing(RCMapper *rcmap, int8_t override_chan, float mixing_gain);
|
bool setup_mixing(RCMapper *rcmap, int8_t override_chan,
|
||||||
|
float mixing_gain, uint16_t manual_rc_mask);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
AP_HAL::UARTDriver &uart;
|
AP_HAL::UARTDriver &uart;
|
||||||
|
@ -166,6 +166,9 @@ struct PACKED page_mixing {
|
|||||||
// is the throttle an angle input?
|
// is the throttle an angle input?
|
||||||
uint8_t throttle_is_angle;
|
uint8_t throttle_is_angle;
|
||||||
|
|
||||||
|
// mask of channels which are pure manual in override
|
||||||
|
uint16_t manual_rc_mask;
|
||||||
|
|
||||||
// enabled needs to be 1 to enable mixing
|
// enabled needs to be 1 to enable mixing
|
||||||
uint8_t enabled;
|
uint8_t enabled;
|
||||||
|
|
||||||
|
@ -141,6 +141,12 @@ void AP_IOMCU_FW::run_mixer(void)
|
|||||||
for (uint8_t i=0; i<IOMCU_MAX_CHANNELS; i++) {
|
for (uint8_t i=0; i<IOMCU_MAX_CHANNELS; i++) {
|
||||||
SRV_Channel::Aux_servo_function_t function = (SRV_Channel::Aux_servo_function_t)mixing.servo_function[i];
|
SRV_Channel::Aux_servo_function_t function = (SRV_Channel::Aux_servo_function_t)mixing.servo_function[i];
|
||||||
uint16_t &pwm = reg_direct_pwm.pwm[i];
|
uint16_t &pwm = reg_direct_pwm.pwm[i];
|
||||||
|
|
||||||
|
if (mixing.manual_rc_mask & (1U<<i)) {
|
||||||
|
// treat as pass-thru if this channel is set in MANUAL_RC_MASK
|
||||||
|
function = SRV_Channel::k_manual;
|
||||||
|
}
|
||||||
|
|
||||||
switch (function) {
|
switch (function) {
|
||||||
case SRV_Channel::k_manual:
|
case SRV_Channel::k_manual:
|
||||||
pwm = rc_input.pwm[i];
|
pwm = rc_input.pwm[i];
|
||||||
|
Loading…
Reference in New Issue
Block a user