Skyward boardcore
Loading...
Searching...
No Matches
SX1278Fsk.cpp
Go to the documentation of this file.
1/* Copyright (c) 2021 Skyward Experimental Rocketry
2 * Author: Davide Mor
3 *
4 * Permission is hereby granted, free of charge, to any person obtaining a copy
5 * of this software and associated documentation files (the "Software"), to deal
6 * in the Software without restriction, including without limitation the rights
7 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
8 * copies of the Software, and to permit persons to whom the Software is
9 * furnished to do so, subject to the following conditions:
10 *
11 * The above copyright notice and this permission notice shall be included in
12 * all copies or substantial portions of the Software.
13 *
14 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
15 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
16 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
17 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
18 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
19 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
20 * THE SOFTWARE.
21 */
22
23#include "SX1278Fsk.h"
24
25#include <kernel/scheduler/scheduler.h>
26#include <utils/Debug.h>
27#include <utils/KernelTime.h>
28
29#include <cassert>
30#include <cmath>
31
32namespace Boardcore
33{
34
35using namespace SX1278;
36using namespace SX1278::Fsk;
37
38long long now() { return Kernel::getOldTick(); }
39
40// Enable:
41// - PayloadReady, PacketSent on DIO0 (mode 00)
42// - FifoLevel on DIO1 (mode 00)
43// - TxReady on DIO3 (mode 01)
44constexpr DioMapping DEFAULT_MAPPING = DioMapping(0, 0, 0, 1, 0, 0, false);
45
47{
48 // First probe for the device
49 if (!checkVersion())
50 return Error::BAD_VALUE;
51
52 Error err;
53 if ((err = configure(config)) != Error::NONE)
54 return err;
55
56 return Error::NONE;
57}
58
60{
61 Lock guard(*this);
63
65 if (version == 0x12)
66 {
67 return true;
68 }
69 else
70 {
71 LOG_ERR(logger, "Wrong chip id: {}", version);
72 return false;
73 }
74}
75
77{
78 // Check that the configuration is actually valid
80 int min_power = pa_boost ? 2 : 0;
82
83 assert(config.power >= min_power && config.power <= max_power &&
84 "[sx1278] Configured power invalid for given frontend!");
85 assert(((config.ocp >= 0 && config.ocp <= 120) ||
86 (config.ocp >= 130 && config.ocp <= 240)) &&
87 "[sx1278] Invalid ocp!");
88 assert(config.freq_dev >= MIN_FREQ_DEV && config.freq_dev <= MAX_FREQ_DEV &&
89 "[sx1278] Invalid freq_dev!");
90 assert(config.freq_rf >= MIN_FREQ_RF && config.freq_rf <= MAX_FREQ_RF &&
91 "[sx1278] Invalid freq_rf");
92
93 // First make sure the device is in fsk and in standby
94 enterFskMode();
95
96 // Set default mode to standby, that way we reset the fifo every time we
97 // enter receive
99 InterruptTrigger::RISING_EDGE, false, false);
100 miosix::Thread::sleep(1);
101
102 // Lock the bus
103 Lock guard(*this);
106
107 // This code is unreliable so it got commented out, the datasheet states
108 // that this triggers during a successful state transition, but for some
109 // reason, this isn't always the case, and can lead to random failures of
110 // the driver initialization. Removing it has no side effects, so that is
111 // what was done.
112 // if (!waitForIrqBusy(guard_mode, RegIrqFlags::MODE_READY, 0, 1000))
113 // return Error::IRQ_TIMEOUT;
114
115 int bitrate = config.bitrate;
116 int freq_dev =
117 std::max(std::min(config.freq_dev, MAX_FREQ_DEV), MIN_FREQ_DEV);
118 int freq_rf = std::max(std::min(config.freq_rf, MAX_FREQ_RF), MIN_FREQ_RF);
119 RegRxBw::RxBw rx_bw = static_cast<RegRxBw::RxBw>(config.rx_bw);
120 RegAfcBw::RxBwAfc afc_bw = static_cast<RegAfcBw::RxBwAfc>(config.afc_bw);
121 int ocp = config.ocp <= 120 ? std::max(std::min(config.ocp, 120), 0)
122 : std::max(std::min(config.ocp, 240), 130);
123 int power = std::max(std::min(config.power, max_power), min_power);
125 static_cast<RegPaRamp::ModulationShaping>(config.shaping);
127 static_cast<RegPacketConfig1::DcFree>(config.dc_free);
128
129 crc_enabled = config.enable_crc;
130
131 {
133
134 // Setup bitrate
135 uint16_t bitrate_raw = FXOSC / bitrate;
137
138 // Setup frequency deviation
139 uint16_t freq_dev_raw = freq_dev / FSTEP;
141
142 // Setup base frequency
143 uint32_t freq_rf_raw = freq_rf / FSTEP;
145
146 // Setup RX bandwidth
148
149 // Setup afc bandwidth
151
152 // Setup reg over-current protection
153 if (config.ocp == 0)
154 spi.writeRegister(REG_OCP, RegOcp::make(0, false));
155 else if (ocp <= 120)
156 spi.writeRegister(REG_OCP, RegOcp::make((ocp - 45) / 5, true));
157 else
158 spi.writeRegister(REG_OCP, RegOcp::make((ocp + 30) / 10, true));
159
160 // Setup sync word
161 spi.writeRegister(
167
168 // Set preamble length
170
171 // Setup shaping
174
175 // Setup power amplifier
176 // [2, 17] or 20 if PA_BOOST
177 // [0, 15] if !PA_BOOST
178 const int MAX_POWER = 0b111;
179 if (!pa_boost)
180 {
181 // Don't use power amplifier boost
183 RegPaConfig::make(power, MAX_POWER, false));
186 }
187 else if (power != 20)
188 {
189 // Run power amplifier boost but not at full power
191 RegPaConfig::make(power - 2, MAX_POWER, true));
194 }
195 else
196 {
197 // Run power amplifier boost at full power
199 RegPaConfig::make(0b1111, MAX_POWER, true));
202 }
203
204 // Setup other registers
205
206 spi.writeRegister(
208 RegRxConfig::make(true, true, true, true, false, false, false));
209
211
212 spi.writeRegister(
216 true));
217
221
222 spi.writeRegister(
228
229 spi.writeRegister(
231 RegPacketConfig2::make(false, false, false,
233
234 // Set maximum payload length
236
237 // Setup threshold to half of the fifo
238 spi.writeRegister(
241 FIFO_LEN / 2,
243
244 spi.writeRegister(REG_NODE_ADRS, 0x00);
246 }
247
248 return Error::NONE;
249}
250
252{
253 Lock guard(*this);
255 InterruptTrigger::RISING_EDGE, false, true);
256
257 // Save the packet locally, we always want to read it all
259
260 uint8_t len = 0;
261 bool crc_ok;
262 IrqFlags flags = 0;
263
264 do
265 {
266 crc_ok = false;
267
268 uint8_t cur_len = 0;
269
270 // Special wait for fifo level/payload ready, release the lock at this
271 // stage
274 0, true);
275 if ((flags & RegIrqFlags::PAYLOAD_READY) != 0 && crc_enabled)
277
278 // Record RSSI here, it's where it is the most accurate
279 last_rx_rssi = getRssi();
280
281 // Now first packet bit
282 {
284 len = spi.readRegister(REG_FIFO);
285
286 int read_size = std::min((int)len, FIFO_LEN / 2);
287 // Skip 0 sized read
288 if (read_size != 0)
290
292 }
293
294 // Then read the other chunks
295 while (cur_len < len)
296 {
300 if ((flags & RegIrqFlags::PAYLOAD_READY) != 0 && crc_enabled)
302
304
305 int read_size = std::min((int)(len - cur_len), FIFO_LEN / 2);
307
309 }
310
311 // For some reason this sometimes happen?
312 } while (len == 0);
313
314 if (len > max_len || (!crc_ok && crc_enabled))
315 return -1;
316
317 // Finally copy the packet to the destination
318 memcpy(pkt, tmp_pkt, len);
319 return len;
320}
321
322bool SX1278Fsk::send(uint8_t* pkt, size_t len)
323{
324 if (len > MTU)
325 return false;
326
327 // This shouldn't be needed, but for some reason the device "lies" about
328 // being ready, so lock up if we are going too fast
329 rateLimitTx();
330
331 Lock guard(*this);
333 InterruptTrigger::FALLING_EDGE, true, false);
334
336
337 // Send first segment
338 {
340
341 spi.writeRegister(REG_FIFO, static_cast<uint8_t>(len));
342
343 int write_size = std::min((int)len, FIFO_LEN - 1);
345
346 pkt += write_size;
347 len -= write_size;
348 }
349
350 // Then send the rest using fifo control
351 while (len > 0)
352 {
353 // Wait for FIFO_LEVEL to go down
355
357
358 int write_size = std::min((int)len, FIFO_LEN / 2);
360
361 pkt += write_size;
362 len -= write_size;
363 }
364
365 // Finally wait for packet sent
366 // Wait for packet sent
368
369 last_tx = now();
370 return true;
371}
372
374{
375 Lock guard(*this);
376 return getFei();
377}
378
379float SX1278Fsk::getLastRxRssi() { return last_rx_rssi; }
380
382{
383 Lock guard(*this);
384 return getRssi();
385}
386
387void SX1278Fsk::enterFskMode()
388{
389 Lock guard(*this);
391
392 // First enter Fsk sleep
393 spi.writeRegister(REG_OP_MODE,
396 miosix::Thread::sleep(1);
397
398 // Then transition to standby
399 spi.writeRegister(REG_OP_MODE,
402 miosix::Thread::sleep(1);
403}
404
405void SX1278Fsk::rateLimitTx()
406{
407 const long long RATE_LIMIT = 2;
408
409 long long delta = now() - last_tx;
410 if (delta <= RATE_LIMIT)
411 miosix::Thread::sleep(RATE_LIMIT - delta);
412}
413
414ISX1278::IrqFlags SX1278Fsk::getIrqFlags()
415{
416 SPITransaction spi(getSpiSlave());
417 return spi.readRegister16(REG_IRQ_FLAGS_1);
418}
419
420void SX1278Fsk::resetIrqFlags(IrqFlags flags)
421{
422 // Mask only resettable flags
426
427 if (flags != 0)
428 {
429 SPITransaction spi(getSpiSlave());
430 spi.writeRegister16(REG_IRQ_FLAGS_1, flags);
431 }
432}
433
434float SX1278Fsk::getRssi()
435{
436 SPITransaction spi(getSpiSlave());
437
438 uint8_t rssi_raw = spi.readRegister(REG_RSSI_VALUE);
439 return static_cast<float>(rssi_raw) * -0.5f;
440}
441
442float SX1278Fsk::getFei()
443{
444 SPITransaction spi(getSpiSlave());
445
446 uint16_t fei_raw = spi.readRegister16(REG_FEI_MSB);
447 return static_cast<float>(fei_raw) * FSTEP;
448}
449
450void SX1278Fsk::setMode(Mode mode)
451{
452 SPITransaction spi(getSpiSlave());
453 spi.writeRegister(REG_OP_MODE,
454 RegOpMode::make(static_cast<RegOpMode::Mode>(mode), true,
456}
457
458void SX1278Fsk::setMapping(SX1278::DioMapping mapping)
459{
460 SPITransaction spi(getSpiSlave());
461 spi.writeRegister16(REG_DIO_MAPPING_1, mapping.raw);
462}
463
464} // namespace Boardcore
#define LOG_ERR(logger,...)
Provides high-level access to the SPI Bus for a single transaction.
uint8_t readRegister(uint8_t reg)
Reads an 8 bit register.
void writeRegisters(uint8_t reg, uint8_t *data, size_t size)
Writes multiple bytes starting from the specified register.
void writeRegister24(uint8_t reg, uint32_t data)
Writes a 24 bit register.
void readRegisters(uint8_t reg, uint8_t *data, size_t size)
Reads multiple bytes starting from the specified register.
void writeRegister(uint8_t reg, uint8_t data)
Writes an 8 bit register.
void writeRegister16(uint8_t reg, uint16_t data)
Writes a 16 bit register.
virtual bool isOnPaBoost()=0
Is this frontend connected to PA_BOOST or RFO_LF/_HF?
virtual int maxInPower()=0
What is the maximum power supported by this frontend?
RAII scoped bus lock guard.
RAII scoped mode lock, requires a previous lock.
void setDefaultMode(Mode mode, DioMapping mapping, InterruptTrigger dio1_trigger, bool set_tx_frontend_on, bool set_rx_frontend_on)
Set default device mode.
IrqFlags checkForIrqAndReset(IrqFlags set_irq, IrqFlags reset_irq)
Returns a mask containing triggered interrupts.
IrqFlags waitForIrq(LockMode &guard, IrqFlags set_irq, IrqFlags reset_irq, bool unlock=false)
Wait for generic irq.
virtual Error init(const Config &config)
Setup the device.
Definition SX1278Fsk.cpp:46
virtual Error configure(const Config &config)
Configure this device on the fly.
Definition SX1278Fsk.cpp:76
static constexpr size_t MTU
Maximum transmittable unit of this driver.
Definition SX1278Fsk.h:44
float getLastRxFei() override
Get the frequency error index in Hz, during last packet receive.
float getLastRxRssi() override
Get the RSSI in dBm, during last packet receive.
float getCurRssi()
Get the current perceived RSSI in dBm.
bool send(uint8_t *pkt, size_t len) override
Send a packet. The function must block until the packet is sent (successfully or not)
ssize_t receive(uint8_t *pkt, size_t max_len) override
Wait until a new packet is received.
long long getOldTick()
Get the current time in milliseconds.
Definition KernelTime.h:43
constexpr uint8_t make(RxBwAfc rx_bw_afc)
Definition SX1278Defs.h:286
constexpr uint8_t make(int fifo_threshold, TxStartCondition tx_start_condition)
Definition SX1278Defs.h:397
constexpr uint8_t make(uint8_t ocp_trim, bool ocp_on)
Definition SX1278Defs.h:223
constexpr uint8_t make(Mode mode, bool low_frequency_mode_on, ModulationType modulation_type)
Definition SX1278Defs.h:161
constexpr uint8_t make(uint8_t output_power, uint8_t max_power, bool pa_select)
Definition SX1278Defs.h:173
constexpr uint8_t make(PaDac pa_dac)
Definition SX1278Defs.h:438
constexpr uint8_t make(PaRamp pa_ramp, ModulationShaping modulation_shaping)
Definition SX1278Defs.h:212
constexpr uint8_t make(CrcWhiteningType crc_whitening_type, AddressFiltering address_filtering, bool crc_auto_clear_off, bool crc_on, DcFree dc_free, PacketFormat packet_format)
Definition SX1278Defs.h:360
constexpr uint8_t make(bool beacon_on, bool io_home_power_frame, bool io_home_on, DataMode data_mode)
Definition SX1278Defs.h:380
constexpr uint8_t make(int tol, Size size, bool on)
Definition SX1278Defs.h:300
constexpr uint8_t make(RxBw rx_bw)
Definition SX1278Defs.h:277
constexpr uint8_t make(bool rx_trigger_rssi_interrupt, bool rx_trigger_preable_detect, bool agc_auto_on, bool afc_auto_on, bool restart_rx_with_pll_lock, bool restart_rx_without_pll_lock, bool restart_rx_on_collision)
Definition SX1278Defs.h:233
constexpr uint8_t make(int size, bool on, PreamblePolarity preamble_polarity, AutoRestartRxMode auto_restart_rx_mode)
Definition SX1278Defs.h:322
constexpr int FIFO_LEN
Length of the internal FIFO.
Definition SX1278Defs.h:140
constexpr int MIN_FREQ_DEV
Definition SX1278Defs.h:58
constexpr float FSTEP
Frequency step (Hz) used in some calculations.
Definition SX1278Defs.h:43
constexpr int MAX_FREQ_DEV
Definition SX1278Defs.h:59
RegDioMapping::Mapping DioMapping
constexpr int MIN_FREQ_RF
Definition SX1278Defs.h:61
constexpr int MAX_FREQ_RF
Definition SX1278Defs.h:62
constexpr int FXOSC
Main oscillator frequency (Hz)
Definition SX1278Defs.h:38
This file includes all the types the logdecoder script will decode.
long long now()
Definition SX1278Fsk.cpp:38
constexpr DioMapping DEFAULT_MAPPING
Definition SX1278Fsk.cpp:44
Represents an actual Dio mapping..
Definition SX1278Defs.h:93
Requested SX1278 configuration.
Definition SX1278Fsk.h:50