-
-
Notifications
You must be signed in to change notification settings - Fork 3k
/
sumh.c
153 lines (116 loc) · 3.9 KB
/
sumh.c
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
/*
* References:
* http://fpv-treff.de/viewtopic.php?f=18&t=1368&start=3020#p44535
* http://fpv-community.de/showthread.php?29033-MultiWii-mit-Graupner-SUMD-SUMH-und-USB-Joystick-auf-ProMicro
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#ifdef USE_SERIALRX_SUMH
#include "common/utils.h"
#include "drivers/time.h"
#include "io/serial.h"
#ifdef USE_TELEMETRY
#include "telemetry/telemetry.h"
#endif
#include "pg/rx.h"
#include "rx/rx.h"
#include "rx/sumh.h"
#define SUMH_BAUDRATE 115200
#define SUMH_MAX_CHANNEL_COUNT 8
#define SUMH_FRAME_SIZE 21
static bool sumhFrameDone = false;
static uint8_t sumhFrame[SUMH_FRAME_SIZE];
static uint32_t sumhChannels[SUMH_MAX_CHANNEL_COUNT];
static serialPort_t *sumhPort;
// Receive ISR callback
static void sumhDataReceive(uint16_t c, void *data)
{
UNUSED(data);
uint32_t sumhTime;
static uint32_t sumhTimeLast, sumhTimeInterval;
static uint8_t sumhFramePosition;
sumhTime = micros();
sumhTimeInterval = sumhTime - sumhTimeLast;
sumhTimeLast = sumhTime;
if (sumhTimeInterval > 5000) {
sumhFramePosition = 0;
}
sumhFrame[sumhFramePosition] = (uint8_t) c;
if (sumhFramePosition == SUMH_FRAME_SIZE - 1) {
// FIXME at this point the value of 'c' is unused and un tested, what should it be, is it important?
sumhFrameDone = true;
} else {
sumhFramePosition++;
}
}
static uint8_t sumhFrameStatus(rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeState);
uint8_t channelIndex;
if (!sumhFrameDone) {
return RX_FRAME_PENDING;
}
sumhFrameDone = false;
if (!((sumhFrame[0] == 0xA8) && (sumhFrame[SUMH_FRAME_SIZE - 2] == 0))) {
return RX_FRAME_PENDING;
}
for (channelIndex = 0; channelIndex < SUMH_MAX_CHANNEL_COUNT; channelIndex++) {
sumhChannels[channelIndex] = (((uint32_t)(sumhFrame[(channelIndex << 1) + 3]) << 8)
+ sumhFrame[(channelIndex << 1) + 4]) / 6.4f - 375;
}
return RX_FRAME_COMPLETE;
}
static float sumhReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{
UNUSED(rxRuntimeState);
if (chan >= SUMH_MAX_CHANNEL_COUNT) {
return 0;
}
return sumhChannels[chan];
}
bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxConfig);
rxRuntimeState->channelCount = SUMH_MAX_CHANNEL_COUNT;
rxRuntimeState->rxRefreshRate = 11000;
rxRuntimeState->rcReadRawFn = sumhReadRawRC;
rxRuntimeState->rcFrameStatusFn = sumhFrameStatus;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {
return false;
}
#ifdef USE_TELEMETRY
bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeState->serialrxProvider);
#else
bool portShared = false;
#endif
sumhPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumhDataReceive, NULL, SUMH_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0));
#ifdef USE_TELEMETRY
if (portShared) {
telemetrySharedPort = sumhPort;
}
#endif
return sumhPort != NULL;
}
#endif