mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_IOMCU: use RC_Channel to populate IOMCU mappings
This commit is contained in:
parent
99e314f49a
commit
cf27ba09d0
@ -1208,7 +1208,7 @@ void AP_IOMCU::bind_dsm(uint8_t mode)
|
||||
setup for mixing. This allows fixed wing aircraft to fly in manual
|
||||
mode if the FMU dies
|
||||
*/
|
||||
bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan,
|
||||
bool AP_IOMCU::setup_mixing(int8_t override_chan,
|
||||
float mixing_gain, uint16_t manual_rc_mask)
|
||||
{
|
||||
if (!is_chibios_backend) {
|
||||
@ -1229,16 +1229,19 @@ bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan,
|
||||
MIX_UPDATE(mixing.servo_function[i], c->get_function());
|
||||
MIX_UPDATE(mixing.servo_reversed[i], c->get_reversed());
|
||||
}
|
||||
// update RCMap
|
||||
MIX_UPDATE(mixing.rc_channel[0], rcmap->roll());
|
||||
MIX_UPDATE(mixing.rc_channel[1], rcmap->pitch());
|
||||
MIX_UPDATE(mixing.rc_channel[2], rcmap->throttle());
|
||||
MIX_UPDATE(mixing.rc_channel[3], rcmap->yaw());
|
||||
auto &xrc = rc();
|
||||
// note that if not all of these channels are specified correctly
|
||||
// in parameters then these may be a "dummy" RC channel pointer.
|
||||
// In that case c->ch() will be zero.
|
||||
const RC_Channel *channels[] {
|
||||
&xrc.get_roll_channel(),
|
||||
&xrc.get_pitch_channel(),
|
||||
&xrc.get_throttle_channel(),
|
||||
&xrc.get_yaw_channel()
|
||||
};
|
||||
for (uint8_t i=0; i<4; i++) {
|
||||
const RC_Channel *c = RC_Channels::rc_channel(mixing.rc_channel[i]-1);
|
||||
if (!c) {
|
||||
continue;
|
||||
}
|
||||
const auto *c = channels[i];
|
||||
MIX_UPDATE(mixing.rc_channel[i], c->ch());
|
||||
MIX_UPDATE(mixing.rc_min[i], c->get_radio_min());
|
||||
MIX_UPDATE(mixing.rc_max[i], c->get_radio_max());
|
||||
MIX_UPDATE(mixing.rc_trim[i], c->get_radio_trim());
|
||||
|
@ -11,7 +11,6 @@
|
||||
#if HAL_WITH_IO_MCU
|
||||
|
||||
#include "iofirmware/ioprotocol.h"
|
||||
#include <AP_RCMapper/AP_RCMapper.h>
|
||||
#include <AP_HAL/RCOutput.h>
|
||||
#include <AP_ESC_Telem/AP_ESC_Telem_Backend.h>
|
||||
|
||||
@ -151,7 +150,7 @@ public:
|
||||
void soft_reboot();
|
||||
|
||||
// setup for FMU failsafe mixing
|
||||
bool setup_mixing(RCMapper *rcmap, int8_t override_chan,
|
||||
bool setup_mixing(int8_t override_chan,
|
||||
float mixing_gain, uint16_t manual_rc_mask);
|
||||
|
||||
// Check if pin number is valid and configured for GPIO
|
||||
|
Loading…
Reference in New Issue
Block a user