MAMBAF405_2022A target
[inav.git] / src / main / rx / mavlink.c
blob8b0c46a0f344db18bf769d6bd6f58dcd504c031c
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <stdlib.h>
21 #include <string.h>
23 #include "platform.h"
24 FILE_COMPILE_FOR_SPEED
25 #ifdef USE_SERIALRX_MAVLINK
27 #include "build/debug.h"
29 #include "common/utils.h"
31 #include "rx/rx.h"
32 #include "rx/mavlink.h"
34 #define MAVLINK_CHANNEL_COUNT 18
35 static uint16_t mavlinkChannelData[MAVLINK_CHANNEL_COUNT];
36 static bool frameReceived;
38 void mavlinkRxHandleMessage(const mavlink_rc_channels_override_t *msg) {
39 if (msg->chan1_raw != 0 && msg->chan1_raw != UINT16_MAX) mavlinkChannelData[0] = msg->chan1_raw;
40 if (msg->chan2_raw != 0 && msg->chan2_raw != UINT16_MAX) mavlinkChannelData[1] = msg->chan2_raw;
41 if (msg->chan3_raw != 0 && msg->chan3_raw != UINT16_MAX) mavlinkChannelData[2] = msg->chan3_raw;
42 if (msg->chan4_raw != 0 && msg->chan4_raw != UINT16_MAX) mavlinkChannelData[3] = msg->chan4_raw;
43 if (msg->chan5_raw != 0 && msg->chan5_raw != UINT16_MAX) mavlinkChannelData[4] = msg->chan5_raw;
44 if (msg->chan6_raw != 0 && msg->chan6_raw != UINT16_MAX) mavlinkChannelData[5] = msg->chan6_raw;
45 if (msg->chan7_raw != 0 && msg->chan7_raw != UINT16_MAX) mavlinkChannelData[6] = msg->chan7_raw;
46 if (msg->chan8_raw != 0 && msg->chan8_raw != UINT16_MAX) mavlinkChannelData[7] = msg->chan8_raw;
47 if (msg->chan9_raw != 0 && msg->chan9_raw < UINT16_MAX - 1) mavlinkChannelData[8] = msg->chan9_raw;
48 if (msg->chan10_raw != 0 && msg->chan10_raw < UINT16_MAX - 1) mavlinkChannelData[9] = msg->chan10_raw;
49 if (msg->chan11_raw != 0 && msg->chan11_raw < UINT16_MAX - 1) mavlinkChannelData[10] = msg->chan11_raw;
50 if (msg->chan12_raw != 0 && msg->chan12_raw < UINT16_MAX - 1) mavlinkChannelData[11] = msg->chan12_raw;
51 if (msg->chan13_raw != 0 && msg->chan13_raw < UINT16_MAX - 1) mavlinkChannelData[12] = msg->chan13_raw;
52 if (msg->chan14_raw != 0 && msg->chan14_raw < UINT16_MAX - 1) mavlinkChannelData[13] = msg->chan14_raw;
53 if (msg->chan15_raw != 0 && msg->chan15_raw < UINT16_MAX - 1) mavlinkChannelData[14] = msg->chan15_raw;
54 if (msg->chan16_raw != 0 && msg->chan16_raw < UINT16_MAX - 1) mavlinkChannelData[15] = msg->chan16_raw;
55 if (msg->chan17_raw != 0 && msg->chan17_raw < UINT16_MAX - 1) mavlinkChannelData[16] = msg->chan17_raw;
56 if (msg->chan18_raw != 0 && msg->chan18_raw < UINT16_MAX - 1) mavlinkChannelData[17] = msg->chan18_raw;
57 frameReceived = true;
60 static uint8_t mavlinkFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
62 UNUSED(rxRuntimeConfig);
63 if (frameReceived) {
64 frameReceived = false;
65 return RX_FRAME_COMPLETE;
67 return RX_FRAME_PENDING;
70 static uint16_t mavlinkReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
72 UNUSED(rxRuntimeConfig);
73 // MAVLink values are sent as PWM values in microseconds so no conversion is needed
74 return mavlinkChannelData[channel];
77 bool mavlinkRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
79 UNUSED(rxConfig);
81 frameReceived = false;
83 rxRuntimeConfig->channelData = mavlinkChannelData;
84 rxRuntimeConfig->channelCount = MAVLINK_CHANNEL_COUNT;
85 rxRuntimeConfig->rxRefreshRate = 11000;
86 rxRuntimeConfig->rcReadRawFn = mavlinkReadRawRC;
87 rxRuntimeConfig->rcFrameStatusFn = mavlinkFrameStatus;
89 for (int ii = 0; ii < MAVLINK_CHANNEL_COUNT; ++ii) {
90 mavlinkChannelData[ii] = (16 * PWM_RANGE_MIDDLE) / 10 - 1408;
93 return true;
96 #endif