Einstein Filho
/
MANGUEBAJA2019_REAR2
Mangue Baja team's code to rear ECU
Revision 0:80950b84a6c4, committed 2019-07-24
- Comitter:
- einsteingustavo
- Date:
- Wed Jul 24 20:04:55 2019 +0000
- Commit message:
- Mangue Baja team's code to rear ECU
Changed in this revision
diff -r 000000000000 -r 80950b84a6c4 .gitignore --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/.gitignore Wed Jul 24 20:04:55 2019 +0000 @@ -0,0 +1,4 @@ +.build +.mbed +projectfiles +*.py*
diff -r 000000000000 -r 80950b84a6c4 BAJADefs/definitions.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/BAJADefs/definitions.h Wed Jul 24 20:04:55 2019 +0000 @@ -0,0 +1,48 @@ +#ifndef DEFINITIONS_H +#define DEFINITIONS_H + +#ifndef MBED_H + #include "mbed.h" + #define MBED_H +#endif + +#define CAN_IER (*((volatile unsigned long *)0x40006414)) + +#define BUFFER_SIZE 50 +#define THROTTLE_MID 0x00 +#define THROTTLE_RUN 0x01 +#define THROTTLE_CHOKE 0x02 + +#define SYNC_ID 0x001 // message for bus sync +#define THROTTLE_ID 0x100 // 1by = throttle state (0x00, 0x01 or 0x02) +#define FLAGS_ID 0x101 // 1by +#define IMU_ACC_ID 0x200 // 8by = accelerometer data (3D) + timestamp +#define IMU_DPS_ID 0x201 // 8by = gyroscope data (3D) + timestamp +#define SPEED_ID 0x300 // 4by = speed + timestamp +#define RPM_ID 0x304 // 4by = rpm + timestamp +#define TEMPERATURE_ID 0x400 // 4by = engine temp. + cvt temp. + timestamp +#define FUEL_ID 0x500 // 3by = fuel level + timestamp + + +typedef struct +{ + int16_t acc_x; + int16_t acc_y; + int16_t acc_z; + int16_t dps_x; + int16_t dps_y; + int16_t dps_z; +} imu_t; + +typedef struct +{ + imu_t imu[4]; + uint16_t rpm; + uint16_t speed; + uint8_t temperature; + uint8_t flags; // MSB - BOX | BUFFER FULL | NC | NC | FUEL_LEVEL | SERVO_ERROR | CHK | RUN - LSB + uint32_t timestamp; +} packet_t; + +#endif +
diff -r 000000000000 -r 80950b84a6c4 CANMsg/CANMsg.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/CANMsg/CANMsg.h Wed Jul 24 20:04:55 2019 +0000 @@ -0,0 +1,67 @@ +#ifndef CANMSG_H +#define CANMSG_H + +/* CAN message container. + * Provides "<<" (append) and ">>" (extract) operators to simplyfy + * adding/getting data items to/from a CAN message. + * Usage is similar to the C++ io-stream operators. + * Data length of CAN message is automatically updated when using "<<" or ">>" operators. + * + * See Wiki page <https://developer.mbed.org/users/hudakz/code/CAN_Hello/> for demo. + */ +#include "CAN.h" + +class CANMsg : public CANMessage +{ +public: + /** Creates empty CAN message. + */ + CANMsg() : + CANMessage(){ } + + /** Creates CAN message with specific content. + */ + CANMsg(int _id, const char *_data, char _len = 8, CANType _type = CANData, CANFormat _format = CANStandard) : + CANMessage(_id, _data, _len, _type, _format){ } + + /** Creates CAN remote message. + */ + CANMsg(int _id, CANFormat _format = CANStandard) : + CANMessage(_id, _format){ } + + /** Clears CAN message content + */ + void clear(int new_id) { + len = 0; + type = CANData; + format = CANStandard; + id = new_id; + memset(data, 0, 8); + }; + + /** Append operator: Appends data (value) to CAN message + */ + template<class T> + CANMsg &operator<<(const T val) { + MBED_ASSERT(len + sizeof(T) <= 8); + //*reinterpret_cast<T*>(&data[len]) = val; // This used to work but now it hangs at run time. + memcpy(&data[len], &val, sizeof(T)); + len += sizeof(T); + return *this; + } + + /** Extract operator: Extracts data (value) from CAN message + */ + template<class T> + CANMsg &operator>>(T& val) { + MBED_ASSERT(sizeof(T) <= len); + val = *reinterpret_cast<T*>(&data[0]); + len -= sizeof(T); + memcpy(data, data + sizeof(T), len); + return *this; + } +}; + +#endif // CANMSG_H + +
diff -r 000000000000 -r 80950b84a6c4 Other_things/CONTRIBUTING.md --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Other_things/CONTRIBUTING.md Wed Jul 24 20:04:55 2019 +0000 @@ -0,0 +1,5 @@ +# Contributing to Mbed OS + +Mbed OS is an open-source, device software platform for the Internet of Things. Contributions are an important part of the platform, and our goal is to make it as simple as possible to become a contributor. + +To encourage productive collaboration, as well as robust, consistent and maintainable code, we have a set of guidelines for [contributing to Mbed OS](https://os.mbed.com/docs/mbed-os/latest/contributing/index.html).
diff -r 000000000000 -r 80950b84a6c4 Other_things/README.md --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Other_things/README.md Wed Jul 24 20:04:55 2019 +0000 @@ -0,0 +1,171 @@ +# Getting started example for Mbed OS + +This guide reviews the steps required to get Blinky with the addition of dynamic OS statistics working on an Mbed OS platform. (Note: To see a rendered example you can import into the Arm Online Compiler, please see our [quick start](https://os.mbed.com/docs/mbed-os/latest/quick-start/online-with-the-online-compiler.html#importing-the-code).) + +Please install [Mbed CLI](https://github.com/ARMmbed/mbed-cli#installing-mbed-cli). + +## Import the example application + +From the command-line, import the example: + +``` +mbed import mbed-os-example-blinky +cd mbed-os-example-blinky +``` + +### Now compile + +Invoke `mbed compile`, and specify the name of your platform and your favorite toolchain (`GCC_ARM`, `ARM`, `IAR`). For example, for the ARM Compiler 5: + +``` +mbed compile -m K64F -t ARM +``` + +Your PC may take a few minutes to compile your code. At the end, you see the following result: + +``` +[snip] ++----------------------------+-------+-------+------+ +| Module | .text | .data | .bss | +|--------------------|-----------|----------|----------| +| [fill] | 98(+0) | 0(+0) | 2211(+0) | +| [lib]/c.a | 27835(+0) | 2472(+0) | 89(+0) | +| [lib]/gcc.a | 3168(+0) | 0(+0) | 0(+0) | +| [lib]/misc | 248(+0) | 8(+0) | 28(+0) | +| [lib]/nosys.a | 32(+0) | 0(+0) | 0(+0) | +| main.o | 924(+0) | 0(+0) | 12(+0) | +| mbed-os/components | 134(+0) | 0(+0) | 0(+0) | +| mbed-os/drivers | 56(+0) | 0(+0) | 0(+0) | +| mbed-os/features | 42(+0) | 0(+0) | 184(+0) | +| mbed-os/hal | 2087(+0) | 8(+0) | 152(+0) | +| mbed-os/platform | 3633(+0) | 260(+0) | 209(+0) | +| mbed-os/rtos | 9370(+0) | 168(+0) | 6053(+0) | +| mbed-os/targets | 9536(+0) | 12(+0) | 382(+0) | +| Subtotals | 57163(+0) | 2928(+0) | 9320(+0) | +Total Static RAM memory (data + bss): 12248(+0) bytes +Total Flash memory (text + data): 60091(+0) bytes + +Image: ./BUILD/K64F/GCC_ARM/mbed-os-example-blinky.bin +``` + +### Program your board + +1. Connect your Mbed device to the computer over USB. +1. Copy the binary file to the Mbed device. +1. Press the reset button to start the program. + +The LED on your platform turns on and off. The main thread will additionally take a snapshot of the device's runtime statistics and display it over serial to your PC. The snapshot includes: + +* System Information: + * Mbed OS Version: Will currently default to 999999 + * Compiler ID + * ARM = 1 + * GCC_ARM = 2 + * IAR = 3 + * [CPUID Register Information](#cpuid-register-information) + * [Compiler Version](#compiler-version) +* CPU Statistics + * Percentage of runtime that the device has spent awake versus in sleep +* Heap Statistics + * Current heap size + * Max heap size which refers to the largest the heap has grown to +* Thread Statistics + * Provides information on all running threads in the OS including + * Thread ID + * Thread Name + * Thread State + * Thread Priority + * Thread Stack Size + * Thread Stack Space + +#### Compiler Version + +| Compiler | Version Layout | +| -------- | -------------- | +| ARM | PVVbbbb (P = Major; VV = Minor; bbbb = build number) | +| GCC | VVRRPP (VV = Version; RR = Revision; PP = Patch) | +| IAR | VRRRPPP (V = Version; RRR = Revision; PPP = Patch) | + +#### CPUID Register Information + +| Bit Field | Field Description | Values | +| --------- | ----------------- | ------ | +|[31:24] | Implementer | 0x41 = ARM | +|[23:20] | Variant | Major revision 0x0 = Revision 0 | +|[19:16] | Architecture | 0xC = Baseline Architecture | +| | | 0xF = Constant (Mainline Architecture) | +|[15:4] | Part Number | 0xC20 = Cortex-M0 | +| | | 0xC60 = Cortex-M0+ | +| | | 0xC23 = Cortex-M3 | +| | | 0xC24 = Cortex-M4 | +| | | 0xC27 = Cortex-M7 | +| | | 0xD20 = Cortex-M23 | +| | | 0xD21 = Cortex-M33 | +|[3:0] | Revision | Minor revision: 0x1 = Patch 1 | + + + +You can view individual examples and additional API information of the statistics collection tools at the bottom of the page in the [related links section](#related-links). + + +### Output + +To view the serial output you can use any terminal client of your choosing such as [PuTTY](http://www.putty.org/) or [CoolTerm](http://freeware.the-meiers.org/). Unless otherwise specified, printf defaults to a baud rate of 9600 on Mbed OS. + +You can find more information on the Mbed OS configuration tools and serial communication in Mbed OS in the related [related links section](#related-links). + +The output should contain the following block transmitted at the blinking LED frequency (actual values may vary depending on your target, build profile, and toolchain): + +``` +=============================== SYSTEM INFO ================================ +Mbed OS Version: 999999 +CPU ID: 0x410fc241 +Compiler ID: 2 +Compiler Version: 60300 +RAM0: Start 0x20000000 Size: 0x30000 +RAM1: Start 0x1fff0000 Size: 0x10000 +ROM0: Start 0x0 Size: 0x100000 +================= CPU STATS ================= +Idle: 98% Usage: 2% +================ HEAP STATS ================= +Current heap: 1096 +Max heap size: 1096 +================ THREAD STATS =============== +ID: 0x20001eac +Name: main_thread +State: 2 +Priority: 24 +Stack Size: 4096 +Stack Space: 3296 + +ID: 0x20000f5c +Name: idle_thread +State: 1 +Priority: 1 +Stack Size: 512 +Stack Space: 352 + +ID: 0x20000f18 +Name: timer_thread +State: 3 +Priority: 40 +Stack Size: 768 +Stack Space: 664 + +``` + +## Troubleshooting + +If you have problems, you can review the [documentation](https://os.mbed.com/docs/latest/tutorials/debugging.html) for suggestions on what could be wrong and how to fix it. + +## Related Links + +* [Mbed OS Stats API](https://os.mbed.com/docs/latest/apis/mbed-statistics.html) +* [Mbed OS Configuration](https://os.mbed.com/docs/latest/reference/configuration.html) +* [Mbed OS Serial Communication](https://os.mbed.com/docs/latest/tutorials/serial-communication.html) + +### License and contributions + +The software is provided under Apache-2.0 license. Contributions to this project are accepted under the same license. Please see contributing.md for more info. + +This project contains code from other projects. The original license text is included in those source files. They must comply with our license guide.
diff -r 000000000000 -r 80950b84a6c4 Other_things/mbed_app.json --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Other_things/mbed_app.json Wed Jul 24 20:04:55 2019 +0000 @@ -0,0 +1,11 @@ +{ + "target_overrides": { + "*": { + "platform.stack-stats-enabled": true, + "platform.heap-stats-enabled": true, + "platform.cpu-stats-enabled": true, + "platform.thread-stats-enabled": true, + "platform.sys-stats-enabled": true + } + } +}
diff -r 000000000000 -r 80950b84a6c4 Other_things/stats_report.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Other_things/stats_report.h Wed Jul 24 20:04:55 2019 +0000 @@ -0,0 +1,132 @@ +/* mbed Microcontroller Library + * Copyright (c) 2018 ARM Limited + * SPDX-License-Identifier: Apache-2.0 + */ + +#ifndef STATS_REPORT_H +#define STATS_REPORT + +#include "mbed.h" + +/** + * System Reporting library. Provides runtime information on device: + * - CPU sleep, idle, and wake times + * - Heap and stack usage + * - Thread information + * - Static system information + */ +class SystemReport { + mbed_stats_heap_t heap_stats; + mbed_stats_cpu_t cpu_stats; + mbed_stats_sys_t sys_stats; + + mbed_stats_thread_t *thread_stats; + uint8_t thread_count; + uint8_t max_thread_count; + uint32_t sample_time_ms; + +public: + /** + * SystemReport - Sample rate in ms is required to handle the CPU percent awake logic + */ + SystemReport(uint32_t sample_rate) : max_thread_count(8), sample_time_ms(sample_rate) + { + thread_stats = new mbed_stats_thread_t[max_thread_count]; + + // Collect the static system information + mbed_stats_sys_get(&sys_stats); + + printf("=============================== SYSTEM INFO ================================\r\n"); + printf("Mbed OS Version: %ld \r\n", sys_stats.os_version); + printf("CPU ID: 0x%lx \r\n", sys_stats.cpu_id); + printf("Compiler ID: %d \r\n", sys_stats.compiler_id); + printf("Compiler Version: %ld \r\n", sys_stats.compiler_version); + + for (int i = 0; i < MBED_MAX_MEM_REGIONS; i++) { + if (sys_stats.ram_size[i] != 0) { + printf("RAM%d: Start 0x%lx Size: 0x%lx \r\n", i, sys_stats.ram_start[i], sys_stats.ram_size[i]); + } + } + for (int i = 0; i < MBED_MAX_MEM_REGIONS; i++) { + if (sys_stats.rom_size[i] != 0) { + printf("ROM%d: Start 0x%lx Size: 0x%lx \r\n", i, sys_stats.rom_start[i], sys_stats.rom_size[i]); + } + } + } + + ~SystemReport(void) + { + free(thread_stats); + } + + /** + * Report on each Mbed OS Platform stats API + */ + void report_state(void) + { + report_cpu_stats(); + report_heap_stats(); + report_thread_stats(); + + // Clear next line to separate subsequent report logs + printf("\r\n"); + } + + /** + * Report CPU idle and awake time in terms of percentage + */ + void report_cpu_stats(void) + { + static uint64_t prev_idle_time = 0; + + printf("================= CPU STATS =================\r\n"); + + // Collect and print cpu stats + mbed_stats_cpu_get(&cpu_stats); + + uint64_t diff = (cpu_stats.idle_time - prev_idle_time); + uint8_t idle = (diff * 100) / (sample_time_ms * 1000); // usec; + uint8_t usage = 100 - ((diff * 100) / (sample_time_ms * 1000)); // usec;; + prev_idle_time = cpu_stats.idle_time; + + printf("Idle: %d%% Usage: %d%% \r\n", idle, usage); + } + + /** + * Report current heap stats. Current heap refers to the current amount of + * allocated heap. Max heap refers to the highest amount of heap allocated + * since reset. + */ + void report_heap_stats(void) + { + printf("================ HEAP STATS =================\r\n"); + + // Collect and print heap stats + mbed_stats_heap_get(&heap_stats); + + printf("Current heap: %lu\r\n", heap_stats.current_size); + printf("Max heap size: %lu\r\n", heap_stats.max_size); + } + + /** + * Report active thread stats + */ + void report_thread_stats(void) + { + printf("================ THREAD STATS ===============\r\n"); + + // Collect and print running thread stats + int count = mbed_stats_thread_get_each(thread_stats, max_thread_count); + + for (int i = 0; i < count; i++) { + printf("ID: 0x%lx \r\n", thread_stats[i].id); + printf("Name: %s \r\n", thread_stats[i].name); + printf("State: %ld \r\n", thread_stats[i].state); + printf("Priority: %ld \r\n", thread_stats[i].priority); + printf("Stack Size: %ld \r\n", thread_stats[i].stack_size); + printf("Stack Space: %ld \r\n", thread_stats[i].stack_space); + } + } +}; + +#endif // STATS_REPORT_H
diff -r 000000000000 -r 80950b84a6c4 RFM69/RFM69.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/RFM69/RFM69.cpp Wed Jul 24 20:04:55 2019 +0000 @@ -0,0 +1,533 @@ +//Port of RFM69 from lowpowerlab +//Sync'd Feb. 6, 2015 +//spi register read/write routines from Karl Zweimuller's RF22 +// +// +// +// ********************************************************************************** +// Driver definition for HopeRF RFM69W/RFM69HW/RFM69CW/RFM69HCW, Semtech SX1231/1231H +// ********************************************************************************** +// Copyright Felix Rusu (2014), felix@lowpowerlab.com +// http://lowpowerlab.com/ +// ********************************************************************************** +// License +// ********************************************************************************** +// This program is free software; you can redistribute it +// and/or modify it 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. +// +// This program is distributed in the hope that it 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 program. +// If not, see <http://www.gnu.org/licenses/>. +// +// Licence can be viewed at +// http://www.gnu.org/licenses/gpl-3.0.txt +// +// Please maintain this license information along with authorship +// and copyright notices in any redistribution of this code +// **********************************************************************************// RF22.cpp +// +// Copyright (C) 2011 Mike McCauley +// $Id: RF22.cpp,v 1.17 2013/02/06 21:33:56 mikem Exp mikem $ +// ported to mbed by Karl Zweimueller +#include "mbed.h" +#include "RFM69.h" +#include <RFM69registers.h> +#include <SPI.h> + +extern Thread eventThread; +extern EventQueue queue; + +volatile uint8_t RFM69::DATA[RF69_MAX_DATA_LEN]; +volatile uint8_t RFM69::_mode; // current transceiver state +volatile uint8_t RFM69::DATALEN; +volatile uint8_t RFM69::SENDERID; +volatile uint8_t RFM69::TARGETID; // should match _address +volatile uint8_t RFM69::PAYLOADLEN; +volatile uint8_t RFM69::ACK_REQUESTED; +volatile uint8_t RFM69::ACK_RECEIVED; // should be polled immediately after sending a packet with ACK request +volatile int16_t RFM69::RSSI; // most accurate RSSI during reception (closest to the reception) + +RFM69::RFM69(PinName mosi, PinName miso, PinName sclk, PinName slaveSelectPin, PinName interrupt): + _slaveSelectPin(slaveSelectPin) , _spi(mosi, miso, sclk), _interrupt(interrupt) { + + // Setup the spi for 8 bit data, high steady state clock, + // second edge capture, with a 1MHz clock rate + _spi.format(8,0); + _spi.frequency(4000000); + _mode = RF69_MODE_STANDBY; + _promiscuousMode = false; + _powerLevel = 31; +} + +bool RFM69::initialize(uint8_t freqBand, uint8_t nodeID, uint8_t networkID) +{ + unsigned long start_to; + const uint8_t CONFIG[][2] = + { + /* 0x01 */ { REG_OPMODE, RF_OPMODE_SEQUENCER_ON | RF_OPMODE_LISTEN_OFF | RF_OPMODE_STANDBY }, + /* 0x02 */ { REG_DATAMODUL, RF_DATAMODUL_DATAMODE_PACKET | RF_DATAMODUL_MODULATIONTYPE_FSK | RF_DATAMODUL_MODULATIONSHAPING_00 }, // no shaping + /* 0x03 */ { REG_BITRATEMSB, RF_BITRATEMSB_4800}, // default: 4.8 KBPS + /* 0x04 */ { REG_BITRATELSB, RF_BITRATELSB_4800}, + /* 0x05 */ { REG_FDEVMSB, RF_FDEVMSB_50000}, // default: 5KHz, (FDEV + BitRate / 2 <= 500KHz) + /* 0x06 */ { REG_FDEVLSB, RF_FDEVLSB_50000}, + + /* 0x07 */ { REG_FRFMSB, (uint8_t) (freqBand==RF69_315MHZ ? RF_FRFMSB_315 : (freqBand==RF69_433MHZ ? RF_FRFMSB_433 : (freqBand==RF69_868MHZ ? RF_FRFMSB_868 : RF_FRFMSB_915))) }, + /* 0x08 */ { REG_FRFMID, (uint8_t) (freqBand==RF69_315MHZ ? RF_FRFMID_315 : (freqBand==RF69_433MHZ ? RF_FRFMID_433 : (freqBand==RF69_868MHZ ? RF_FRFMID_868 : RF_FRFMID_915))) }, + /* 0x09 */ { REG_FRFLSB, (uint8_t) (freqBand==RF69_315MHZ ? RF_FRFLSB_315 : (freqBand==RF69_433MHZ ? RF_FRFLSB_433 : (freqBand==RF69_868MHZ ? RF_FRFLSB_868 : RF_FRFLSB_915))) }, + + // looks like PA1 and PA2 are not implemented on RFM69W, hence the max output power is 13dBm + // +17dBm and +20dBm are possible on RFM69HW + // +13dBm formula: Pout = -18 + OutputPower (with PA0 or PA1**) + // +17dBm formula: Pout = -14 + OutputPower (with PA1 and PA2)** + // +20dBm formula: Pout = -11 + OutputPower (with PA1 and PA2)** and high power PA settings (section 3.3.7 in datasheet) + ///* 0x11 */ { REG_PALEVEL, RF_PALEVEL_PA0_ON | RF_PALEVEL_PA1_OFF | RF_PALEVEL_PA2_OFF | RF_PALEVEL_OUTPUTPOWER_11111}, + ///* 0x13 */ { REG_OCP, RF_OCP_ON | RF_OCP_TRIM_95 }, // over current protection (default is 95mA) + + // RXBW defaults are { REG_RXBW, RF_RXBW_DCCFREQ_010 | RF_RXBW_MANT_24 | RF_RXBW_EXP_5} (RxBw: 10.4KHz) + /* 0x19 */ { REG_RXBW, RF_RXBW_DCCFREQ_010 | RF_RXBW_MANT_16 | RF_RXBW_EXP_2 }, // (BitRate < 2 * RxBw) + //for BR-19200: /* 0x19 */ { REG_RXBW, RF_RXBW_DCCFREQ_010 | RF_RXBW_MANT_24 | RF_RXBW_EXP_3 }, + /* 0x25 */ { REG_DIOMAPPING1, RF_DIOMAPPING1_DIO0_01 }, // DIO0 is the only IRQ we're using + /* 0x26 */ { REG_DIOMAPPING2, RF_DIOMAPPING2_CLKOUT_OFF }, // DIO5 ClkOut disable for power saving + /* 0x28 */ { REG_IRQFLAGS2, RF_IRQFLAGS2_FIFOOVERRUN }, // writing to this bit ensures that the FIFO & status flags are reset + /* 0x29 */ { REG_RSSITHRESH, 220 }, // must be set to dBm = (-Sensitivity / 2), default is 0xE4 = 228 so -114dBm + ///* 0x2D */ { REG_PREAMBLELSB, RF_PREAMBLESIZE_LSB_VALUE } // default 3 preamble bytes 0xAAAAAA + /* 0x2E */ { REG_SYNCCONFIG, RF_SYNC_ON | RF_SYNC_FIFOFILL_AUTO | RF_SYNC_SIZE_2 | RF_SYNC_TOL_0 }, + /* 0x2F */ { REG_SYNCVALUE1, 0x2D }, // attempt to make this compatible with sync1 byte of RFM12B lib + /* 0x30 */ { REG_SYNCVALUE2, networkID }, // NETWORK ID + /* 0x37 */ { REG_PACKETCONFIG1, RF_PACKET1_FORMAT_VARIABLE | RF_PACKET1_DCFREE_OFF | RF_PACKET1_CRC_ON | RF_PACKET1_CRCAUTOCLEAR_ON | RF_PACKET1_ADRSFILTERING_OFF }, + /* 0x38 */ { REG_PAYLOADLENGTH, 66 }, // in variable length mode: the max frame size, not used in TX + ///* 0x39 */ { REG_NODEADRS, nodeID }, // turned off because we're not using address filtering + /* 0x3C */ { REG_FIFOTHRESH, RF_FIFOTHRESH_TXSTART_FIFONOTEMPTY | RF_FIFOTHRESH_VALUE }, // TX on FIFO not empty + /* 0x3D */ { REG_PACKETCONFIG2, RF_PACKET2_RXRESTARTDELAY_2BITS | RF_PACKET2_AUTORXRESTART_ON | RF_PACKET2_AES_OFF }, // RXRESTARTDELAY must match transmitter PA ramp-down time (bitrate dependent) + //for BR-19200: /* 0x3D */ { REG_PACKETCONFIG2, RF_PACKET2_RXRESTARTDELAY_NONE | RF_PACKET2_AUTORXRESTART_ON | RF_PACKET2_AES_OFF }, // RXRESTARTDELAY must match transmitter PA ramp-down time (bitrate dependent) + /* 0x6F */ { REG_TESTDAGC, RF_DAGC_IMPROVED_LOWBETA0 }, // run DAGC continuously in RX mode for Fading Margin Improvement, recommended default for AfcLowBetaOn=0 + {255, 0} + }; +// Timer for ms waits + t.start(); + _slaveSelectPin = 1; + + // Setup the spi for 8 bit data : 1RW-bit 7 adressbit and 8 databit + // second edge capture, with a 10MHz clock rate + _spi.format(8,0); + _spi.frequency(4000000); + +#define TIME_OUT 50 + + start_to = t.read_ms() ; + + do writeReg(REG_SYNCVALUE1, 0xaa); while (readReg(REG_SYNCVALUE1) != 0xaa && t.read_ms()-start_to < TIME_OUT); + if (t.read_ms()-start_to >= TIME_OUT) return (false); + + // Set time out + start_to = t.read_ms() ; + do writeReg(REG_SYNCVALUE1, 0x55); while (readReg(REG_SYNCVALUE1) != 0x55 && t.read_ms()-start_to < TIME_OUT); + if (t.read_ms()-start_to >= TIME_OUT) return (false); + for (uint8_t i = 0; CONFIG[i][0] != 255; i++) + writeReg(CONFIG[i][0], CONFIG[i][1]); + + // Encryption is persistent between resets and can trip you up during debugging. + // Disable it during initialization so we always start from a known state. + encrypt(0); + + setHighPower(_isRFM69HW); // called regardless if it's a RFM69W or RFM69HW + setMode(RF69_MODE_STANDBY); + // Set up interrupt handler + start_to = t.read_ms() ; + while (((readReg(REG_IRQFLAGS1) & RF_IRQFLAGS1_MODEREADY) == 0x00) && t.read_ms()-start_to < TIME_OUT); // Wait for ModeReady + if (t.read_ms()-start_to >= TIME_OUT) return (false); + + + _interrupt.rise(this, &RFM69::isr0); + _address = nodeID; + return true; +} +// return the frequency (in Hz) +uint32_t RFM69::getFrequency() +{ + return RF69_FSTEP * (((uint32_t) readReg(REG_FRFMSB) << 16) + ((uint16_t) readReg(REG_FRFMID) << 8) + readReg(REG_FRFLSB)); +} + +// set the frequency (in Hz) +void RFM69::setFrequency(uint32_t freqHz) +{ + uint8_t oldMode = _mode; + if (oldMode == RF69_MODE_TX) { + setMode(RF69_MODE_RX); + } + freqHz /= RF69_FSTEP; // divide down by FSTEP to get FRF + writeReg(REG_FRFMSB, freqHz >> 16); + writeReg(REG_FRFMID, freqHz >> 8); + writeReg(REG_FRFLSB, freqHz); + if (oldMode == RF69_MODE_RX) { + setMode(RF69_MODE_SYNTH); + } + setMode(oldMode); +} + +void RFM69::setMode(uint8_t newMode) +{ + if (newMode == _mode) + return; + + switch (newMode) { + case RF69_MODE_TX: + writeReg(REG_OPMODE, (readReg(REG_OPMODE) & 0xE3) | RF_OPMODE_TRANSMITTER); + if (_isRFM69HW) setHighPowerRegs(true); + break; + case RF69_MODE_RX: + writeReg(REG_OPMODE, (readReg(REG_OPMODE) & 0xE3) | RF_OPMODE_RECEIVER); + if (_isRFM69HW) setHighPowerRegs(false); + break; + case RF69_MODE_SYNTH: + writeReg(REG_OPMODE, (readReg(REG_OPMODE) & 0xE3) | RF_OPMODE_SYNTHESIZER); + break; + case RF69_MODE_STANDBY: + writeReg(REG_OPMODE, (readReg(REG_OPMODE) & 0xE3) | RF_OPMODE_STANDBY); + break; + case RF69_MODE_SLEEP: + writeReg(REG_OPMODE, (readReg(REG_OPMODE) & 0xE3) | RF_OPMODE_SLEEP); + break; + default: + return; + } + + // we are using packet mode, so this check is not really needed + // but waiting for mode ready is necessary when going from sleep because the FIFO may not be immediately available from previous mode + while (_mode == RF69_MODE_SLEEP && (readReg(REG_IRQFLAGS1) & RF_IRQFLAGS1_MODEREADY) == 0x00); // wait for ModeReady + _mode = newMode; +} + +void RFM69::sleep() { + setMode(RF69_MODE_SLEEP); +} + +void RFM69::setAddress(uint8_t addr) +{ + _address = addr; + writeReg(REG_NODEADRS, _address); +} + +void RFM69::setNetwork(uint8_t networkID) +{ + writeReg(REG_SYNCVALUE2, networkID); +} + +// set output power: 0 = min, 31 = max +// this results in a "weaker" transmitted signal, and directly results in a lower RSSI at the receiver +void RFM69::setPowerLevel(uint8_t powerLevel) +{ + _powerLevel = powerLevel; + writeReg(REG_PALEVEL, (readReg(REG_PALEVEL) & 0xE0) | (_powerLevel > 31 ? 31 : _powerLevel)); +} + +bool RFM69::canSend() +{ + if (_mode == RF69_MODE_RX && PAYLOADLEN == 0 && readRSSI() < CSMA_LIMIT) // if signal stronger than -100dBm is detected assume channel activity + { + setMode(RF69_MODE_STANDBY); + return true; + } + return false; +} + +void RFM69::send(uint8_t toAddress, const void* buffer, uint8_t bufferSize, bool requestACK, bool sendACK) +{ + writeReg(REG_PACKETCONFIG2, (readReg(REG_PACKETCONFIG2) & 0xFB) | RF_PACKET2_RXRESTART); // avoid RX deadlocks + uint32_t now = t.read_ms(); + while (!canSend() && t.read_ms() - now < RF69_CSMA_LIMIT_MS) receiveDone(); + sendFrame(toAddress, buffer, bufferSize, requestACK, sendACK); +} + +// to increase the chance of getting a packet across, call this function instead of send +// and it handles all the ACK requesting/retrying for you :) +// The only twist is that you have to manually listen to ACK requests on the other side and send back the ACKs +// The reason for the semi-automaton is that the lib is interrupt driven and +// requires user action to read the received data and decide what to do with it +// replies usually take only 5..8ms at 50kbps@915MHz +bool RFM69::sendWithRetry(uint8_t toAddress, const void* buffer, uint8_t bufferSize, uint8_t retries, uint8_t retryWaitTime) { + uint32_t sentTime; + for (uint8_t i = 0; i <= retries; i++) + { + send(toAddress, buffer, bufferSize, true); + sentTime = t.read_ms(); + while (t.read_ms() - sentTime < retryWaitTime) + { + if (ACKReceived(toAddress)) + { + //Serial.print(" ~ms:"); Serial.print(t.read_ms() - sentTime); + return true; + } + } + //Serial.print(" RETRY#"); Serial.println(i + 1); + } + return false; +} + +// should be polled immediately after sending a packet with ACK request +bool RFM69::ACKReceived(uint8_t fromNodeID) { + if (receiveDone()) + return (SENDERID == fromNodeID || fromNodeID == RF69_BROADCAST_ADDR) && ACK_RECEIVED; + return false; +} + +// check whether an ACK was requested in the last received packet (non-broadcasted packet) +bool RFM69::ACKRequested() { + return ACK_REQUESTED && (TARGETID != RF69_BROADCAST_ADDR); +} + +// should be called immediately after reception in case sender wants ACK +void RFM69::sendACK(const void* buffer, uint8_t bufferSize) { + uint8_t sender = SENDERID; + int16_t _RSSI = RSSI; // save payload received RSSI value + writeReg(REG_PACKETCONFIG2, (readReg(REG_PACKETCONFIG2) & 0xFB) | RF_PACKET2_RXRESTART); // avoid RX deadlocks + uint32_t now = t.read_ms(); + while (!canSend() && t.read_ms() - now < RF69_CSMA_LIMIT_MS) receiveDone(); + sendFrame(sender, buffer, bufferSize, false, true); + RSSI = _RSSI; // restore payload RSSI +} + +void RFM69::sendFrame(uint8_t toAddress, const void* buffer, uint8_t bufferSize, bool requestACK, bool sendACK) +{ + setMode(RF69_MODE_STANDBY); // turn off receiver to prevent reception while filling fifo + while ((readReg(REG_IRQFLAGS1) & RF_IRQFLAGS1_MODEREADY) == 0x00); // wait for ModeReady + writeReg(REG_DIOMAPPING1, RF_DIOMAPPING1_DIO0_00); // DIO0 is "Packet Sent" + if (bufferSize > RF69_MAX_DATA_LEN) bufferSize = RF69_MAX_DATA_LEN; + + // control byte + uint8_t CTLbyte = 0x00; + if (sendACK) + CTLbyte = 0x80; + else if (requestACK) + CTLbyte = 0x40; + + select(); + _spi.write(REG_FIFO | 0x80); + _spi.write(bufferSize + 3); + _spi.write(toAddress); + _spi.write(_address); + _spi.write(CTLbyte); + + for (uint8_t i = 0; i < bufferSize; i++) + _spi.write(((uint8_t*) buffer)[i]); + unselect(); + + // no need to wait for transmit mode to be ready since its handled by the radio + setMode(RF69_MODE_TX); + uint32_t txStart = t.read_ms(); + while (_interrupt == 0 && t.read_ms() - txStart < RF69_TX_LIMIT_MS); // wait for DIO0 to turn HIGH signalling transmission finish + //while (readReg(REG_IRQFLAGS2) & RF_IRQFLAGS2_PACKETSENT == 0x00); // wait for ModeReady + setMode(RF69_MODE_STANDBY); +} +// ON = disable filtering to capture all frames on network +// OFF = enable node/broadcast filtering to capture only frames sent to this/broadcast address +void RFM69::promiscuous(bool onOff) { + _promiscuousMode = onOff; + //writeReg(REG_PACKETCONFIG1, (readReg(REG_PACKETCONFIG1) & 0xF9) | (onOff ? RF_PACKET1_ADRSFILTERING_OFF : RF_PACKET1_ADRSFILTERING_NODEBROADCAST)); +} + +void RFM69::setHighPower(bool onOff) { + _isRFM69HW = onOff; + writeReg(REG_OCP, _isRFM69HW ? RF_OCP_OFF : RF_OCP_ON); + if (_isRFM69HW) // turning ON + writeReg(REG_PALEVEL, (readReg(REG_PALEVEL) & 0x1F) | RF_PALEVEL_PA1_ON | RF_PALEVEL_PA2_ON); // enable P1 & P2 amplifier stages + else + writeReg(REG_PALEVEL, RF_PALEVEL_PA0_ON | RF_PALEVEL_PA1_OFF | RF_PALEVEL_PA2_OFF | _powerLevel); // enable P0 only +} + +void RFM69::setHighPowerRegs(bool onOff) { + writeReg(REG_TESTPA1, onOff ? 0x5D : 0x55); + writeReg(REG_TESTPA2, onOff ? 0x7C : 0x70); +} + +/* +void RFM69::setCS(uint8_t newSPISlaveSelect) { + DigitalOut _slaveSelectPin(newSPISlaveSelect); + _slaveSelectPin = 1; +} +*/ +// for debugging +void RFM69::readAllRegs() +{ + uint8_t regVal,regAddr; + + for (regAddr = 1; regAddr <= 0x4F; regAddr++) + { + select(); + _spi.write(regAddr & 0x7F); // send address + r/w bit + regVal = _spi.write(0); + + /* Serial.print(regAddr, HEX); + Serial.print(" - "); + Serial.print(regVal,HEX); + Serial.print(" - "); + Serial.println(regVal,BIN);*/ + } + unselect(); +} + +uint8_t RFM69::readTemperature(int8_t calFactor) // returns centigrade +{ + uint8_t oldMode = _mode; + + setMode(RF69_MODE_STANDBY); + writeReg(REG_TEMP1, RF_TEMP1_MEAS_START); + while ((readReg(REG_TEMP1) & RF_TEMP1_MEAS_RUNNING)); + setMode(oldMode); + + return ~readReg(REG_TEMP2) + COURSE_TEMP_COEF + calFactor; // 'complement' corrects the slope, rising temp = rising val +} // COURSE_TEMP_COEF puts reading in the ballpark, user can add additional correction + +void RFM69::rcCalibration() +{ + writeReg(REG_OSC1, RF_OSC1_RCCAL_START); + while ((readReg(REG_OSC1) & RF_OSC1_RCCAL_DONE) == 0x00); +} +// C++ level interrupt handler for this instance +void RFM69::interruptHandler() { + + if (_mode == RF69_MODE_RX && (readReg(REG_IRQFLAGS2) & RF_IRQFLAGS2_PAYLOADREADY)) + { + setMode(RF69_MODE_STANDBY); + select(); + + _spi.write(REG_FIFO & 0x7F); + PAYLOADLEN = _spi.write(0); + PAYLOADLEN = PAYLOADLEN > 66 ? 66 : PAYLOADLEN; // precaution + TARGETID = _spi.write(0); + if(!(_promiscuousMode || TARGETID == _address || TARGETID == RF69_BROADCAST_ADDR) // match this node's address, or broadcast address or anything in promiscuous mode + || PAYLOADLEN < 3) // address situation could receive packets that are malformed and don't fit this libraries extra fields + { + PAYLOADLEN = 0; + unselect(); + receiveBegin(); + return; + } + + DATALEN = PAYLOADLEN - 3; + SENDERID = _spi.write(0); + uint8_t CTLbyte = _spi.write(0); + + ACK_RECEIVED = CTLbyte & 0x80; // extract ACK-received flag + ACK_REQUESTED = CTLbyte & 0x40; // extract ACK-requested flag + + for (uint8_t i = 0; i < DATALEN; i++) + { + DATA[i] = _spi.write(0); + } + if (DATALEN < RF69_MAX_DATA_LEN) DATA[DATALEN] = 0; // add null at end of string + unselect(); + setMode(RF69_MODE_RX); + } + RSSI = readRSSI(); +} + + +// These are low level functions that call the interrupt handler for the correct instance of RFM69. +void RFM69::isr0() +{ + queue.call(this, &RFM69::interruptHandler); +} + +void RFM69::receiveBegin() { + DATALEN = 0; + SENDERID = 0; + TARGETID = 0; + PAYLOADLEN = 0; + ACK_REQUESTED = 0; + ACK_RECEIVED = 0; + RSSI = 0; + if (readReg(REG_IRQFLAGS2) & RF_IRQFLAGS2_PAYLOADREADY) + writeReg(REG_PACKETCONFIG2, (readReg(REG_PACKETCONFIG2) & 0xFB) | RF_PACKET2_RXRESTART); // avoid RX deadlocks + writeReg(REG_DIOMAPPING1, RF_DIOMAPPING1_DIO0_01); // set DIO0 to "PAYLOADREADY" in receive mode + setMode(RF69_MODE_RX); + _interrupt.enable_irq(); +} + +bool RFM69::receiveDone() { + _interrupt.disable_irq(); // re-enabled in unselect() via setMode() or via receiveBegin() + if (_mode == RF69_MODE_RX && PAYLOADLEN > 0) + { + setMode(RF69_MODE_STANDBY); // enables interrupts + return true; + } + else if (_mode == RF69_MODE_RX) // already in RX no payload yet + { + _interrupt.enable_irq(); // explicitly re-enable interrupts + return false; + } + receiveBegin(); + return false; +} + +// To enable encryption: radio.encrypt("ABCDEFGHIJKLMNOP"); +// To disable encryption: radio.encrypt(null) or radio.encrypt(0) +// KEY HAS TO BE 16 bytes !!! +void RFM69::encrypt(const char* key) { + setMode(RF69_MODE_STANDBY); + if (key != 0) + { + select(); + _spi.write(REG_AESKEY1 | 0x80); + for (uint8_t i = 0; i < 16; i++) + _spi.write(key[i]); + unselect(); + } + writeReg(REG_PACKETCONFIG2, (readReg(REG_PACKETCONFIG2) & 0xFE) | (key ? 1 : 0)); +} + +int16_t RFM69::readRSSI(bool forceTrigger) { + int16_t rssi = 0; + if (forceTrigger) + { + // RSSI trigger not needed if DAGC is in continuous mode + writeReg(REG_RSSICONFIG, RF_RSSI_START); + while ((readReg(REG_RSSICONFIG) & RF_RSSI_DONE) == 0x00); // wait for RSSI_Ready + } + rssi = -readReg(REG_RSSIVALUE); + rssi >>= 1; + return rssi; +} + +uint8_t RFM69::readReg(uint8_t addr) +{ + select(); + _spi.write(addr & 0x7F); // Send the address with the write mask off + uint8_t val = _spi.write(0); // The written value is ignored, reg value is read + unselect(); + return val; +} + +void RFM69::writeReg(uint8_t addr, uint8_t value) +{ + select(); + _spi.write(addr | 0x80); // Send the address with the write mask on + _spi.write(value); // New value follows + unselect(); + } + +// select the transceiver +void RFM69::select() { + _interrupt.disable_irq(); // Disable Interrupts +/* // set RFM69 SPI settings + SPI.setDataMode(SPI_MODE0); + SPI.setBitOrder(MSBFIRST); + SPI.setClockDivider(SPI_CLOCK_DIV4); // decided to slow down from DIV2 after SPI stalling in some instances, especially visible on mega1284p when RFM69 and FLASH chip both present */ + _slaveSelectPin = 0; +} + +// UNselect the transceiver chip +void RFM69::unselect() { + _slaveSelectPin = 1; + _interrupt.enable_irq(); // Enable Interrupts +} +
diff -r 000000000000 -r 80950b84a6c4 RFM69/RFM69.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/RFM69/RFM69.h Wed Jul 24 20:04:55 2019 +0000 @@ -0,0 +1,120 @@ +// ********************************************************************************** +// Driver definition for HopeRF RFM69W/RFM69HW/RFM69CW/RFM69HCW, Semtech SX1231/1231H +// ********************************************************************************** +// Copyright Felix Rusu (2014), felix@lowpowerlab.com +// http://lowpowerlab.com/ +// ********************************************************************************** +// License +// ********************************************************************************** +// This program is free software; you can redistribute it +// and/or modify it 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. +// +// This program is distributed in the hope that it 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 program. +// If not, see <http://www.gnu.org/licenses/>. +// +// Licence can be viewed at +// http://www.gnu.org/licenses/gpl-3.0.txt +// +// Please maintain this license information along with authorship +// and copyright notices in any redistribution of this code +// ********************************************************************************** +#ifndef RFM69_h +#define RFM69_h +#include <mbed.h> // assumes Arduino IDE v1.0 or greater + +#define RF69_MAX_DATA_LEN 61 // to take advantage of the built in AES/CRC we want to limit the frame size to the internal FIFO size (66 bytes - 3 bytes overhead - 2 bytes crc) +//#define RF69_SPI_CS SS // SS is the SPI slave select pin, for instance D10 on ATmega328 + +#define CSMA_LIMIT -90 // upper RX signal sensitivity threshold in dBm for carrier sense access +#define RF69_MODE_SLEEP 0 // XTAL OFF +#define RF69_MODE_STANDBY 1 // XTAL ON +#define RF69_MODE_SYNTH 2 // PLL ON +#define RF69_MODE_RX 3 // RX MODE +#define RF69_MODE_TX 4 // TX MODE + +// available frequency bands +#define RF69_315MHZ 31 // non trivial values to avoid misconfiguration +#define RF69_433MHZ 43 +#define RF69_868MHZ 86 +#define RF69_915MHZ 91 + +#define null 0 +#define COURSE_TEMP_COEF -90 // puts the temperature reading in the ballpark, user can fine tune the returned value +#define RF69_BROADCAST_ADDR 255 +#define RF69_CSMA_LIMIT_MS 200 +#define RF69_TX_LIMIT_MS 200 +#define RF69_FSTEP 61.03515625 // == FXOSC / 2^19 = 32MHz / 2^19 (p13 in datasheet) + +class RFM69 { + public: + static volatile uint8_t DATA[RF69_MAX_DATA_LEN]; // recv/xmit buf, including header & crc bytes + static volatile uint8_t DATALEN; + static volatile uint8_t SENDERID; + static volatile uint8_t TARGETID; // should match _address + static volatile uint8_t PAYLOADLEN; + static volatile uint8_t ACK_REQUESTED; + static volatile uint8_t ACK_RECEIVED; // should be polled immediately after sending a packet with ACK request + static volatile int16_t RSSI; // most accurate RSSI during reception (closest to the reception) + static volatile uint8_t _mode; // should be protected? + + RFM69(PinName mosi, PinName miso, PinName sclk, PinName slaveSelectPin, PinName interrupt); + + bool initialize(uint8_t freqBand, uint8_t ID, uint8_t networkID=1); + void setAddress(uint8_t addr); + void setNetwork(uint8_t networkID); + bool canSend(); + void send(uint8_t toAddress, const void* buffer, uint8_t bufferSize, bool requestACK=false, bool sendACK=false); + bool sendWithRetry(uint8_t toAddress, const void* buffer, uint8_t bufferSize, uint8_t retries=2, uint8_t retryWaitTime=40); // 40ms roundtrip req for 61byte packets + bool receiveDone(); + bool ACKReceived(uint8_t fromNodeID); + bool ACKRequested(); + void sendACK(const void* buffer = "", uint8_t bufferSize=0); + uint32_t getFrequency(); + void setFrequency(uint32_t freqHz); + void encrypt(const char* key); +// void setCS(uint8_t newSPISlaveSelect); + int16_t readRSSI(bool forceTrigger=false); + void promiscuous(bool onOff=true); + void setHighPower(bool onOFF=true); // has to be called after initialize() for RFM69HW + void setPowerLevel(uint8_t level); // reduce/increase transmit power level + void sleep(); + uint8_t readTemperature(int8_t calFactor=0); // get CMOS temperature (8bit) + void rcCalibration(); // calibrate the internal RC oscillator for use in wide temperature variations - see datasheet section [4.3.5. RC Timer Accuracy] + + // allow hacking registers by making these public + uint8_t readReg(uint8_t addr); + void writeReg(uint8_t addr, uint8_t val); + void readAllRegs(); + + protected: + void virtual interruptHandler(); + void isr0(); + void sendFrame(uint8_t toAddress, const void* buffer, uint8_t size, bool requestACK=false, bool sendACK=false); + + static RFM69* selfPointer; + DigitalOut _slaveSelectPin; + InterruptIn _interrupt; + uint8_t _address; + Timer t; + bool _promiscuousMode; + uint8_t _powerLevel; + bool _isRFM69HW; + SPI _spi; + void receiveBegin(); + void setMode(uint8_t mode); + void setHighPowerRegs(bool onOff); + void select(); + void unselect(); +}; + +#endif
diff -r 000000000000 -r 80950b84a6c4 RFM69/RFM69registers.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/RFM69/RFM69registers.h Wed Jul 24 20:04:55 2019 +0000 @@ -0,0 +1,1109 @@ +// ********************************************************************************** +// Registers used in driver definition for HopeRF RFM69W/RFM69HW, Semtech SX1231/1231H +// ********************************************************************************** +// Copyright Felix Rusu (2015), felix@lowpowerlab.com +// http://lowpowerlab.com/ +// ********************************************************************************** +// License +// ********************************************************************************** +// This program is free software; you can redistribute it +// and/or modify it under the terms of the GNU General +// Public License as published by the Free Software +// Foundation; either version 2 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it 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 program; if not, write +// to the Free Software Foundation, Inc., +// 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +// +// Licence can be viewed at +// http://www.fsf.org/licenses/gpl.txt +// +// Please maintain this license information along with authorship +// and copyright notices in any redistribution of this code +// ********************************************************************************** +// RFM69/SX1231 Internal registers addresses +//************************************************** +#define REG_FIFO 0x00 +#define REG_OPMODE 0x01 +#define REG_DATAMODUL 0x02 +#define REG_BITRATEMSB 0x03 +#define REG_BITRATELSB 0x04 +#define REG_FDEVMSB 0x05 +#define REG_FDEVLSB 0x06 +#define REG_FRFMSB 0x07 +#define REG_FRFMID 0x08 +#define REG_FRFLSB 0x09 +#define REG_OSC1 0x0A +#define REG_AFCCTRL 0x0B +#define REG_LOWBAT 0x0C +#define REG_LISTEN1 0x0D +#define REG_LISTEN2 0x0E +#define REG_LISTEN3 0x0F +#define REG_VERSION 0x10 +#define REG_PALEVEL 0x11 +#define REG_PARAMP 0x12 +#define REG_OCP 0x13 +#define REG_AGCREF 0x14 // not present on RFM69/SX1231 +#define REG_AGCTHRESH1 0x15 // not present on RFM69/SX1231 +#define REG_AGCTHRESH2 0x16 // not present on RFM69/SX1231 +#define REG_AGCTHRESH3 0x17 // not present on RFM69/SX1231 +#define REG_LNA 0x18 +#define REG_RXBW 0x19 +#define REG_AFCBW 0x1A +#define REG_OOKPEAK 0x1B +#define REG_OOKAVG 0x1C +#define REG_OOKFIX 0x1D +#define REG_AFCFEI 0x1E +#define REG_AFCMSB 0x1F +#define REG_AFCLSB 0x20 +#define REG_FEIMSB 0x21 +#define REG_FEILSB 0x22 +#define REG_RSSICONFIG 0x23 +#define REG_RSSIVALUE 0x24 +#define REG_DIOMAPPING1 0x25 +#define REG_DIOMAPPING2 0x26 +#define REG_IRQFLAGS1 0x27 +#define REG_IRQFLAGS2 0x28 +#define REG_RSSITHRESH 0x29 +#define REG_RXTIMEOUT1 0x2A +#define REG_RXTIMEOUT2 0x2B +#define REG_PREAMBLEMSB 0x2C +#define REG_PREAMBLELSB 0x2D +#define REG_SYNCCONFIG 0x2E +#define REG_SYNCVALUE1 0x2F +#define REG_SYNCVALUE2 0x30 +#define REG_SYNCVALUE3 0x31 +#define REG_SYNCVALUE4 0x32 +#define REG_SYNCVALUE5 0x33 +#define REG_SYNCVALUE6 0x34 +#define REG_SYNCVALUE7 0x35 +#define REG_SYNCVALUE8 0x36 +#define REG_PACKETCONFIG1 0x37 +#define REG_PAYLOADLENGTH 0x38 +#define REG_NODEADRS 0x39 +#define REG_BROADCASTADRS 0x3A +#define REG_AUTOMODES 0x3B +#define REG_FIFOTHRESH 0x3C +#define REG_PACKETCONFIG2 0x3D +#define REG_AESKEY1 0x3E +#define REG_AESKEY2 0x3F +#define REG_AESKEY3 0x40 +#define REG_AESKEY4 0x41 +#define REG_AESKEY5 0x42 +#define REG_AESKEY6 0x43 +#define REG_AESKEY7 0x44 +#define REG_AESKEY8 0x45 +#define REG_AESKEY9 0x46 +#define REG_AESKEY10 0x47 +#define REG_AESKEY11 0x48 +#define REG_AESKEY12 0x49 +#define REG_AESKEY13 0x4A +#define REG_AESKEY14 0x4B +#define REG_AESKEY15 0x4C +#define REG_AESKEY16 0x4D +#define REG_TEMP1 0x4E +#define REG_TEMP2 0x4F +#define REG_TESTLNA 0x58 +#define REG_TESTPA1 0x5A // only present on RFM69HW/SX1231H +#define REG_TESTPA2 0x5C // only present on RFM69HW/SX1231H +#define REG_TESTDAGC 0x6F + +//****************************************************** +// RF69/SX1231 bit control definition +//****************************************************** + +// RegOpMode +#define RF_OPMODE_SEQUENCER_OFF 0x80 +#define RF_OPMODE_SEQUENCER_ON 0x00 // Default + +#define RF_OPMODE_LISTEN_ON 0x40 +#define RF_OPMODE_LISTEN_OFF 0x00 // Default + +#define RF_OPMODE_LISTENABORT 0x20 + +#define RF_OPMODE_SLEEP 0x00 +#define RF_OPMODE_STANDBY 0x04 // Default +#define RF_OPMODE_SYNTHESIZER 0x08 +#define RF_OPMODE_TRANSMITTER 0x0C +#define RF_OPMODE_RECEIVER 0x10 + + +// RegDataModul +#define RF_DATAMODUL_DATAMODE_PACKET 0x00 // Default +#define RF_DATAMODUL_DATAMODE_CONTINUOUS 0x40 +#define RF_DATAMODUL_DATAMODE_CONTINUOUSNOBSYNC 0x60 + +#define RF_DATAMODUL_MODULATIONTYPE_FSK 0x00 // Default +#define RF_DATAMODUL_MODULATIONTYPE_OOK 0x08 + +#define RF_DATAMODUL_MODULATIONSHAPING_00 0x00 // Default +#define RF_DATAMODUL_MODULATIONSHAPING_01 0x01 +#define RF_DATAMODUL_MODULATIONSHAPING_10 0x02 +#define RF_DATAMODUL_MODULATIONSHAPING_11 0x03 + + +// RegBitRate (bits/sec) example bit rates +#define RF_BITRATEMSB_1200 0x68 +#define RF_BITRATELSB_1200 0x2B +#define RF_BITRATEMSB_2400 0x34 +#define RF_BITRATELSB_2400 0x15 +#define RF_BITRATEMSB_4800 0x1A // Default +#define RF_BITRATELSB_4800 0x0B // Default +#define RF_BITRATEMSB_9600 0x0D +#define RF_BITRATELSB_9600 0x05 +#define RF_BITRATEMSB_19200 0x06 +#define RF_BITRATELSB_19200 0x83 +#define RF_BITRATEMSB_38400 0x03 +#define RF_BITRATELSB_38400 0x41 + +#define RF_BITRATEMSB_38323 0x03 +#define RF_BITRATELSB_38323 0x43 + +#define RF_BITRATEMSB_34482 0x03 +#define RF_BITRATELSB_34482 0xA0 + +#define RF_BITRATEMSB_76800 0x01 +#define RF_BITRATELSB_76800 0xA1 +#define RF_BITRATEMSB_153600 0x00 +#define RF_BITRATELSB_153600 0xD0 +#define RF_BITRATEMSB_57600 0x02 +#define RF_BITRATELSB_57600 0x2C +#define RF_BITRATEMSB_115200 0x01 +#define RF_BITRATELSB_115200 0x16 +#define RF_BITRATEMSB_12500 0x0A +#define RF_BITRATELSB_12500 0x00 +#define RF_BITRATEMSB_25000 0x05 +#define RF_BITRATELSB_25000 0x00 +#define RF_BITRATEMSB_50000 0x02 +#define RF_BITRATELSB_50000 0x80 +#define RF_BITRATEMSB_100000 0x01 +#define RF_BITRATELSB_100000 0x40 +#define RF_BITRATEMSB_150000 0x00 +#define RF_BITRATELSB_150000 0xD5 +#define RF_BITRATEMSB_200000 0x00 +#define RF_BITRATELSB_200000 0xA0 +#define RF_BITRATEMSB_250000 0x00 +#define RF_BITRATELSB_250000 0x80 +#define RF_BITRATEMSB_300000 0x00 +#define RF_BITRATELSB_300000 0x6B +#define RF_BITRATEMSB_32768 0x03 +#define RF_BITRATELSB_32768 0xD1 +// custom bit rates +#define RF_BITRATEMSB_55555 0x02 +#define RF_BITRATELSB_55555 0x40 +#define RF_BITRATEMSB_200KBPS 0x00 +#define RF_BITRATELSB_200KBPS 0xa0 + + +// RegFdev - frequency deviation (Hz) +#define RF_FDEVMSB_2000 0x00 +#define RF_FDEVLSB_2000 0x21 +#define RF_FDEVMSB_5000 0x00 // Default +#define RF_FDEVLSB_5000 0x52 // Default +#define RF_FDEVMSB_7500 0x00 +#define RF_FDEVLSB_7500 0x7B +#define RF_FDEVMSB_10000 0x00 +#define RF_FDEVLSB_10000 0xA4 +#define RF_FDEVMSB_15000 0x00 +#define RF_FDEVLSB_15000 0xF6 +#define RF_FDEVMSB_20000 0x01 +#define RF_FDEVLSB_20000 0x48 +#define RF_FDEVMSB_25000 0x01 +#define RF_FDEVLSB_25000 0x9A +#define RF_FDEVMSB_30000 0x01 +#define RF_FDEVLSB_30000 0xEC +#define RF_FDEVMSB_35000 0x02 +#define RF_FDEVLSB_35000 0x3D +#define RF_FDEVMSB_40000 0x02 +#define RF_FDEVLSB_40000 0x8F +#define RF_FDEVMSB_45000 0x02 +#define RF_FDEVLSB_45000 0xE1 +#define RF_FDEVMSB_50000 0x03 +#define RF_FDEVLSB_50000 0x33 +#define RF_FDEVMSB_55000 0x03 +#define RF_FDEVLSB_55000 0x85 +#define RF_FDEVMSB_60000 0x03 +#define RF_FDEVLSB_60000 0xD7 +#define RF_FDEVMSB_65000 0x04 +#define RF_FDEVLSB_65000 0x29 +#define RF_FDEVMSB_70000 0x04 +#define RF_FDEVLSB_70000 0x7B +#define RF_FDEVMSB_75000 0x04 +#define RF_FDEVLSB_75000 0xCD +#define RF_FDEVMSB_80000 0x05 +#define RF_FDEVLSB_80000 0x1F +#define RF_FDEVMSB_85000 0x05 +#define RF_FDEVLSB_85000 0x71 +#define RF_FDEVMSB_90000 0x05 +#define RF_FDEVLSB_90000 0xC3 +#define RF_FDEVMSB_95000 0x06 +#define RF_FDEVLSB_95000 0x14 +#define RF_FDEVMSB_100000 0x06 +#define RF_FDEVLSB_100000 0x66 +#define RF_FDEVMSB_110000 0x07 +#define RF_FDEVLSB_110000 0x0A +#define RF_FDEVMSB_120000 0x07 +#define RF_FDEVLSB_120000 0xAE +#define RF_FDEVMSB_130000 0x08 +#define RF_FDEVLSB_130000 0x52 +#define RF_FDEVMSB_140000 0x08 +#define RF_FDEVLSB_140000 0xF6 +#define RF_FDEVMSB_150000 0x09 +#define RF_FDEVLSB_150000 0x9A +#define RF_FDEVMSB_160000 0x0A +#define RF_FDEVLSB_160000 0x3D +#define RF_FDEVMSB_170000 0x0A +#define RF_FDEVLSB_170000 0xE1 +#define RF_FDEVMSB_180000 0x0B +#define RF_FDEVLSB_180000 0x85 +#define RF_FDEVMSB_190000 0x0C +#define RF_FDEVLSB_190000 0x29 +#define RF_FDEVMSB_200000 0x0C +#define RF_FDEVLSB_200000 0xCD +#define RF_FDEVMSB_210000 0x0D +#define RF_FDEVLSB_210000 0x71 +#define RF_FDEVMSB_220000 0x0E +#define RF_FDEVLSB_220000 0x14 +#define RF_FDEVMSB_230000 0x0E +#define RF_FDEVLSB_230000 0xB8 +#define RF_FDEVMSB_240000 0x0F +#define RF_FDEVLSB_240000 0x5C +#define RF_FDEVMSB_250000 0x10 +#define RF_FDEVLSB_250000 0x00 +#define RF_FDEVMSB_260000 0x10 +#define RF_FDEVLSB_260000 0xA4 +#define RF_FDEVMSB_270000 0x11 +#define RF_FDEVLSB_270000 0x48 +#define RF_FDEVMSB_280000 0x11 +#define RF_FDEVLSB_280000 0xEC +#define RF_FDEVMSB_290000 0x12 +#define RF_FDEVLSB_290000 0x8F +#define RF_FDEVMSB_300000 0x13 +#define RF_FDEVLSB_300000 0x33 + + +// RegFrf (MHz) - carrier frequency +// 315Mhz band +#define RF_FRFMSB_314 0x4E +#define RF_FRFMID_314 0x80 +#define RF_FRFLSB_314 0x00 +#define RF_FRFMSB_315 0x4E +#define RF_FRFMID_315 0xC0 +#define RF_FRFLSB_315 0x00 +#define RF_FRFMSB_316 0x4F +#define RF_FRFMID_316 0x00 +#define RF_FRFLSB_316 0x00 +// 433mhz band +#define RF_FRFMSB_433 0x6C +#define RF_FRFMID_433 0x40 +#define RF_FRFLSB_433 0x00 +#define RF_FRFMSB_434 0x6C +#define RF_FRFMID_434 0x80 +#define RF_FRFLSB_434 0x00 +#define RF_FRFMSB_435 0x6C +#define RF_FRFMID_435 0xC0 +#define RF_FRFLSB_435 0x00 +// 868Mhz band +#define RF_FRFMSB_863 0xD7 +#define RF_FRFMID_863 0xC0 +#define RF_FRFLSB_863 0x00 +#define RF_FRFMSB_864 0xD8 +#define RF_FRFMID_864 0x00 +#define RF_FRFLSB_864 0x00 +#define RF_FRFMSB_865 0xD8 +#define RF_FRFMID_865 0x40 +#define RF_FRFLSB_865 0x00 +#define RF_FRFMSB_866 0xD8 +#define RF_FRFMID_866 0x80 +#define RF_FRFLSB_866 0x00 +#define RF_FRFMSB_867 0xD8 +#define RF_FRFMID_867 0xC0 +#define RF_FRFLSB_867 0x00 +#define RF_FRFMSB_868 0xD9 +#define RF_FRFMID_868 0x00 +#define RF_FRFLSB_868 0x00 +#define RF_FRFMSB_869 0xD9 +#define RF_FRFMID_869 0x40 +#define RF_FRFLSB_869 0x00 +#define RF_FRFMSB_870 0xD9 +#define RF_FRFMID_870 0x80 +#define RF_FRFLSB_870 0x00 +// 915Mhz band +#define RF_FRFMSB_902 0xE1 +#define RF_FRFMID_902 0x80 +#define RF_FRFLSB_902 0x00 +#define RF_FRFMSB_903 0xE1 +#define RF_FRFMID_903 0xC0 +#define RF_FRFLSB_903 0x00 +#define RF_FRFMSB_904 0xE2 +#define RF_FRFMID_904 0x00 +#define RF_FRFLSB_904 0x00 +#define RF_FRFMSB_905 0xE2 +#define RF_FRFMID_905 0x40 +#define RF_FRFLSB_905 0x00 +#define RF_FRFMSB_906 0xE2 +#define RF_FRFMID_906 0x80 +#define RF_FRFLSB_906 0x00 +#define RF_FRFMSB_907 0xE2 +#define RF_FRFMID_907 0xC0 +#define RF_FRFLSB_907 0x00 +#define RF_FRFMSB_908 0xE3 +#define RF_FRFMID_908 0x00 +#define RF_FRFLSB_908 0x00 +#define RF_FRFMSB_909 0xE3 +#define RF_FRFMID_909 0x40 +#define RF_FRFLSB_909 0x00 +#define RF_FRFMSB_910 0xE3 +#define RF_FRFMID_910 0x80 +#define RF_FRFLSB_910 0x00 +#define RF_FRFMSB_911 0xE3 +#define RF_FRFMID_911 0xC0 +#define RF_FRFLSB_911 0x00 +#define RF_FRFMSB_912 0xE4 +#define RF_FRFMID_912 0x00 +#define RF_FRFLSB_912 0x00 +#define RF_FRFMSB_913 0xE4 +#define RF_FRFMID_913 0x40 +#define RF_FRFLSB_913 0x00 +#define RF_FRFMSB_914 0xE4 +#define RF_FRFMID_914 0x80 +#define RF_FRFLSB_914 0x00 +#define RF_FRFMSB_915 0xE4 // Default +#define RF_FRFMID_915 0xC0 // Default +#define RF_FRFLSB_915 0x00 // Default +#define RF_FRFMSB_916 0xE5 +#define RF_FRFMID_916 0x00 +#define RF_FRFLSB_916 0x00 +#define RF_FRFMSB_917 0xE5 +#define RF_FRFMID_917 0x40 +#define RF_FRFLSB_917 0x00 +#define RF_FRFMSB_918 0xE5 +#define RF_FRFMID_918 0x80 +#define RF_FRFLSB_918 0x00 +#define RF_FRFMSB_919 0xE5 +#define RF_FRFMID_919 0xC0 +#define RF_FRFLSB_919 0x00 +#define RF_FRFMSB_920 0xE6 +#define RF_FRFMID_920 0x00 +#define RF_FRFLSB_920 0x00 +#define RF_FRFMSB_921 0xE6 +#define RF_FRFMID_921 0x40 +#define RF_FRFLSB_921 0x00 +#define RF_FRFMSB_922 0xE6 +#define RF_FRFMID_922 0x80 +#define RF_FRFLSB_922 0x00 +#define RF_FRFMSB_923 0xE6 +#define RF_FRFMID_923 0xC0 +#define RF_FRFLSB_923 0x00 +#define RF_FRFMSB_924 0xE7 +#define RF_FRFMID_924 0x00 +#define RF_FRFLSB_924 0x00 +#define RF_FRFMSB_925 0xE7 +#define RF_FRFMID_925 0x40 +#define RF_FRFLSB_925 0x00 +#define RF_FRFMSB_926 0xE7 +#define RF_FRFMID_926 0x80 +#define RF_FRFLSB_926 0x00 +#define RF_FRFMSB_927 0xE7 +#define RF_FRFMID_927 0xC0 +#define RF_FRFLSB_927 0x00 +#define RF_FRFMSB_928 0xE8 +#define RF_FRFMID_928 0x00 +#define RF_FRFLSB_928 0x00 + + +// RegOsc1 +#define RF_OSC1_RCCAL_START 0x80 +#define RF_OSC1_RCCAL_DONE 0x40 + + +// RegAfcCtrl +#define RF_AFCCTRL_LOWBETA_OFF 0x00 // Default +#define RF_AFCCTRL_LOWBETA_ON 0x20 + + +// RegLowBat +#define RF_LOWBAT_MONITOR 0x10 +#define RF_LOWBAT_ON 0x08 +#define RF_LOWBAT_OFF 0x00 // Default + +#define RF_LOWBAT_TRIM_1695 0x00 +#define RF_LOWBAT_TRIM_1764 0x01 +#define RF_LOWBAT_TRIM_1835 0x02 // Default +#define RF_LOWBAT_TRIM_1905 0x03 +#define RF_LOWBAT_TRIM_1976 0x04 +#define RF_LOWBAT_TRIM_2045 0x05 +#define RF_LOWBAT_TRIM_2116 0x06 +#define RF_LOWBAT_TRIM_2185 0x07 + + +// RegListen1 +#define RF_LISTEN1_RESOL_64 0x50 +#define RF_LISTEN1_RESOL_4100 0xA0 // Default +#define RF_LISTEN1_RESOL_262000 0xF0 + +#define RF_LISTEN1_RESOL_IDLE_64 0x40 +#define RF_LISTEN1_RESOL_IDLE_4100 0x80 // Default +#define RF_LISTEN1_RESOL_IDLE_262000 0xC0 + +#define RF_LISTEN1_RESOL_RX_64 0x10 +#define RF_LISTEN1_RESOL_RX_4100 0x20 // Default +#define RF_LISTEN1_RESOL_RX_262000 0x30 + +#define RF_LISTEN1_CRITERIA_RSSI 0x00 // Default +#define RF_LISTEN1_CRITERIA_RSSIANDSYNC 0x08 + +#define RF_LISTEN1_END_00 0x00 +#define RF_LISTEN1_END_01 0x02 // Default +#define RF_LISTEN1_END_10 0x04 + + +// RegListen2 +#define RF_LISTEN2_COEFIDLE_VALUE 0xF5 // Default + + +// RegListen3 +#define RF_LISTEN3_COEFRX_VALUE 0x20 // Default + + +// RegVersion +#define RF_VERSION_VER 0x24 // Default + + +// RegPaLevel +#define RF_PALEVEL_PA0_ON 0x80 // Default +#define RF_PALEVEL_PA0_OFF 0x00 +#define RF_PALEVEL_PA1_ON 0x40 +#define RF_PALEVEL_PA1_OFF 0x00 // Default +#define RF_PALEVEL_PA2_ON 0x20 +#define RF_PALEVEL_PA2_OFF 0x00 // Default + +#define RF_PALEVEL_OUTPUTPOWER_00000 0x00 +#define RF_PALEVEL_OUTPUTPOWER_00001 0x01 +#define RF_PALEVEL_OUTPUTPOWER_00010 0x02 +#define RF_PALEVEL_OUTPUTPOWER_00011 0x03 +#define RF_PALEVEL_OUTPUTPOWER_00100 0x04 +#define RF_PALEVEL_OUTPUTPOWER_00101 0x05 +#define RF_PALEVEL_OUTPUTPOWER_00110 0x06 +#define RF_PALEVEL_OUTPUTPOWER_00111 0x07 +#define RF_PALEVEL_OUTPUTPOWER_01000 0x08 +#define RF_PALEVEL_OUTPUTPOWER_01001 0x09 +#define RF_PALEVEL_OUTPUTPOWER_01010 0x0A +#define RF_PALEVEL_OUTPUTPOWER_01011 0x0B +#define RF_PALEVEL_OUTPUTPOWER_01100 0x0C +#define RF_PALEVEL_OUTPUTPOWER_01101 0x0D +#define RF_PALEVEL_OUTPUTPOWER_01110 0x0E +#define RF_PALEVEL_OUTPUTPOWER_01111 0x0F +#define RF_PALEVEL_OUTPUTPOWER_10000 0x10 +#define RF_PALEVEL_OUTPUTPOWER_10001 0x11 +#define RF_PALEVEL_OUTPUTPOWER_10010 0x12 +#define RF_PALEVEL_OUTPUTPOWER_10011 0x13 +#define RF_PALEVEL_OUTPUTPOWER_10100 0x14 +#define RF_PALEVEL_OUTPUTPOWER_10101 0x15 +#define RF_PALEVEL_OUTPUTPOWER_10110 0x16 +#define RF_PALEVEL_OUTPUTPOWER_10111 0x17 +#define RF_PALEVEL_OUTPUTPOWER_11000 0x18 +#define RF_PALEVEL_OUTPUTPOWER_11001 0x19 +#define RF_PALEVEL_OUTPUTPOWER_11010 0x1A +#define RF_PALEVEL_OUTPUTPOWER_11011 0x1B +#define RF_PALEVEL_OUTPUTPOWER_11100 0x1C +#define RF_PALEVEL_OUTPUTPOWER_11101 0x1D +#define RF_PALEVEL_OUTPUTPOWER_11110 0x1E +#define RF_PALEVEL_OUTPUTPOWER_11111 0x1F // Default + + +// RegPaRamp +#define RF_PARAMP_3400 0x00 +#define RF_PARAMP_2000 0x01 +#define RF_PARAMP_1000 0x02 +#define RF_PARAMP_500 0x03 +#define RF_PARAMP_250 0x04 +#define RF_PARAMP_125 0x05 +#define RF_PARAMP_100 0x06 +#define RF_PARAMP_62 0x07 +#define RF_PARAMP_50 0x08 +#define RF_PARAMP_40 0x09 // Default +#define RF_PARAMP_31 0x0A +#define RF_PARAMP_25 0x0B +#define RF_PARAMP_20 0x0C +#define RF_PARAMP_15 0x0D +#define RF_PARAMP_12 0x0E +#define RF_PARAMP_10 0x0F + + +// RegOcp +#define RF_OCP_OFF 0x0F +#define RF_OCP_ON 0x1A // Default + +#define RF_OCP_TRIM_45 0x00 +#define RF_OCP_TRIM_50 0x01 +#define RF_OCP_TRIM_55 0x02 +#define RF_OCP_TRIM_60 0x03 +#define RF_OCP_TRIM_65 0x04 +#define RF_OCP_TRIM_70 0x05 +#define RF_OCP_TRIM_75 0x06 +#define RF_OCP_TRIM_80 0x07 +#define RF_OCP_TRIM_85 0x08 +#define RF_OCP_TRIM_90 0x09 +#define RF_OCP_TRIM_95 0x0A // Default +#define RF_OCP_TRIM_100 0x0B +#define RF_OCP_TRIM_105 0x0C +#define RF_OCP_TRIM_110 0x0D +#define RF_OCP_TRIM_115 0x0E +#define RF_OCP_TRIM_120 0x0F + + +// RegAgcRef - not present on RFM69/SX1231 +#define RF_AGCREF_AUTO_ON 0x40 // Default +#define RF_AGCREF_AUTO_OFF 0x00 + +#define RF_AGCREF_LEVEL_MINUS80 0x00 // Default +#define RF_AGCREF_LEVEL_MINUS81 0x01 +#define RF_AGCREF_LEVEL_MINUS82 0x02 +#define RF_AGCREF_LEVEL_MINUS83 0x03 +#define RF_AGCREF_LEVEL_MINUS84 0x04 +#define RF_AGCREF_LEVEL_MINUS85 0x05 +#define RF_AGCREF_LEVEL_MINUS86 0x06 +#define RF_AGCREF_LEVEL_MINUS87 0x07 +#define RF_AGCREF_LEVEL_MINUS88 0x08 +#define RF_AGCREF_LEVEL_MINUS89 0x09 +#define RF_AGCREF_LEVEL_MINUS90 0x0A +#define RF_AGCREF_LEVEL_MINUS91 0x0B +#define RF_AGCREF_LEVEL_MINUS92 0x0C +#define RF_AGCREF_LEVEL_MINUS93 0x0D +#define RF_AGCREF_LEVEL_MINUS94 0x0E +#define RF_AGCREF_LEVEL_MINUS95 0x0F +#define RF_AGCREF_LEVEL_MINUS96 0x10 +#define RF_AGCREF_LEVEL_MINUS97 0x11 +#define RF_AGCREF_LEVEL_MINUS98 0x12 +#define RF_AGCREF_LEVEL_MINUS99 0x13 +#define RF_AGCREF_LEVEL_MINUS100 0x14 +#define RF_AGCREF_LEVEL_MINUS101 0x15 +#define RF_AGCREF_LEVEL_MINUS102 0x16 +#define RF_AGCREF_LEVEL_MINUS103 0x17 +#define RF_AGCREF_LEVEL_MINUS104 0x18 +#define RF_AGCREF_LEVEL_MINUS105 0x19 +#define RF_AGCREF_LEVEL_MINUS106 0x1A +#define RF_AGCREF_LEVEL_MINUS107 0x1B +#define RF_AGCREF_LEVEL_MINUS108 0x1C +#define RF_AGCREF_LEVEL_MINUS109 0x1D +#define RF_AGCREF_LEVEL_MINUS110 0x1E +#define RF_AGCREF_LEVEL_MINUS111 0x1F +#define RF_AGCREF_LEVEL_MINUS112 0x20 +#define RF_AGCREF_LEVEL_MINUS113 0x21 +#define RF_AGCREF_LEVEL_MINUS114 0x22 +#define RF_AGCREF_LEVEL_MINUS115 0x23 +#define RF_AGCREF_LEVEL_MINUS116 0x24 +#define RF_AGCREF_LEVEL_MINUS117 0x25 +#define RF_AGCREF_LEVEL_MINUS118 0x26 +#define RF_AGCREF_LEVEL_MINUS119 0x27 +#define RF_AGCREF_LEVEL_MINUS120 0x28 +#define RF_AGCREF_LEVEL_MINUS121 0x29 +#define RF_AGCREF_LEVEL_MINUS122 0x2A +#define RF_AGCREF_LEVEL_MINUS123 0x2B +#define RF_AGCREF_LEVEL_MINUS124 0x2C +#define RF_AGCREF_LEVEL_MINUS125 0x2D +#define RF_AGCREF_LEVEL_MINUS126 0x2E +#define RF_AGCREF_LEVEL_MINUS127 0x2F +#define RF_AGCREF_LEVEL_MINUS128 0x30 +#define RF_AGCREF_LEVEL_MINUS129 0x31 +#define RF_AGCREF_LEVEL_MINUS130 0x32 +#define RF_AGCREF_LEVEL_MINUS131 0x33 +#define RF_AGCREF_LEVEL_MINUS132 0x34 +#define RF_AGCREF_LEVEL_MINUS133 0x35 +#define RF_AGCREF_LEVEL_MINUS134 0x36 +#define RF_AGCREF_LEVEL_MINUS135 0x37 +#define RF_AGCREF_LEVEL_MINUS136 0x38 +#define RF_AGCREF_LEVEL_MINUS137 0x39 +#define RF_AGCREF_LEVEL_MINUS138 0x3A +#define RF_AGCREF_LEVEL_MINUS139 0x3B +#define RF_AGCREF_LEVEL_MINUS140 0x3C +#define RF_AGCREF_LEVEL_MINUS141 0x3D +#define RF_AGCREF_LEVEL_MINUS142 0x3E +#define RF_AGCREF_LEVEL_MINUS143 0x3F + + +// RegAgcThresh1 - not present on RFM69/SX1231 +#define RF_AGCTHRESH1_SNRMARGIN_000 0x00 +#define RF_AGCTHRESH1_SNRMARGIN_001 0x20 +#define RF_AGCTHRESH1_SNRMARGIN_010 0x40 +#define RF_AGCTHRESH1_SNRMARGIN_011 0x60 +#define RF_AGCTHRESH1_SNRMARGIN_100 0x80 +#define RF_AGCTHRESH1_SNRMARGIN_101 0xA0 // Default +#define RF_AGCTHRESH1_SNRMARGIN_110 0xC0 +#define RF_AGCTHRESH1_SNRMARGIN_111 0xE0 + +#define RF_AGCTHRESH1_STEP1_0 0x00 +#define RF_AGCTHRESH1_STEP1_1 0x01 +#define RF_AGCTHRESH1_STEP1_2 0x02 +#define RF_AGCTHRESH1_STEP1_3 0x03 +#define RF_AGCTHRESH1_STEP1_4 0x04 +#define RF_AGCTHRESH1_STEP1_5 0x05 +#define RF_AGCTHRESH1_STEP1_6 0x06 +#define RF_AGCTHRESH1_STEP1_7 0x07 +#define RF_AGCTHRESH1_STEP1_8 0x08 +#define RF_AGCTHRESH1_STEP1_9 0x09 +#define RF_AGCTHRESH1_STEP1_10 0x0A +#define RF_AGCTHRESH1_STEP1_11 0x0B +#define RF_AGCTHRESH1_STEP1_12 0x0C +#define RF_AGCTHRESH1_STEP1_13 0x0D +#define RF_AGCTHRESH1_STEP1_14 0x0E +#define RF_AGCTHRESH1_STEP1_15 0x0F +#define RF_AGCTHRESH1_STEP1_16 0x10 // Default +#define RF_AGCTHRESH1_STEP1_17 0x11 +#define RF_AGCTHRESH1_STEP1_18 0x12 +#define RF_AGCTHRESH1_STEP1_19 0x13 +#define RF_AGCTHRESH1_STEP1_20 0x14 +#define RF_AGCTHRESH1_STEP1_21 0x15 +#define RF_AGCTHRESH1_STEP1_22 0x16 +#define RF_AGCTHRESH1_STEP1_23 0x17 +#define RF_AGCTHRESH1_STEP1_24 0x18 +#define RF_AGCTHRESH1_STEP1_25 0x19 +#define RF_AGCTHRESH1_STEP1_26 0x1A +#define RF_AGCTHRESH1_STEP1_27 0x1B +#define RF_AGCTHRESH1_STEP1_28 0x1C +#define RF_AGCTHRESH1_STEP1_29 0x1D +#define RF_AGCTHRESH1_STEP1_30 0x1E +#define RF_AGCTHRESH1_STEP1_31 0x1F + + +// RegAgcThresh2 - not present on RFM69/SX1231 +#define RF_AGCTHRESH2_STEP2_0 0x00 +#define RF_AGCTHRESH2_STEP2_1 0x10 +#define RF_AGCTHRESH2_STEP2_2 0x20 +#define RF_AGCTHRESH2_STEP2_3 0x30 // XXX wrong -- Default +#define RF_AGCTHRESH2_STEP2_4 0x40 +#define RF_AGCTHRESH2_STEP2_5 0x50 +#define RF_AGCTHRESH2_STEP2_6 0x60 +#define RF_AGCTHRESH2_STEP2_7 0x70 // default +#define RF_AGCTHRESH2_STEP2_8 0x80 +#define RF_AGCTHRESH2_STEP2_9 0x90 +#define RF_AGCTHRESH2_STEP2_10 0xA0 +#define RF_AGCTHRESH2_STEP2_11 0xB0 +#define RF_AGCTHRESH2_STEP2_12 0xC0 +#define RF_AGCTHRESH2_STEP2_13 0xD0 +#define RF_AGCTHRESH2_STEP2_14 0xE0 +#define RF_AGCTHRESH2_STEP2_15 0xF0 + +#define RF_AGCTHRESH2_STEP3_0 0x00 +#define RF_AGCTHRESH2_STEP3_1 0x01 +#define RF_AGCTHRESH2_STEP3_2 0x02 +#define RF_AGCTHRESH2_STEP3_3 0x03 +#define RF_AGCTHRESH2_STEP3_4 0x04 +#define RF_AGCTHRESH2_STEP3_5 0x05 +#define RF_AGCTHRESH2_STEP3_6 0x06 +#define RF_AGCTHRESH2_STEP3_7 0x07 +#define RF_AGCTHRESH2_STEP3_8 0x08 +#define RF_AGCTHRESH2_STEP3_9 0x09 +#define RF_AGCTHRESH2_STEP3_10 0x0A +#define RF_AGCTHRESH2_STEP3_11 0x0B // Default +#define RF_AGCTHRESH2_STEP3_12 0x0C +#define RF_AGCTHRESH2_STEP3_13 0x0D +#define RF_AGCTHRESH2_STEP3_14 0x0E +#define RF_AGCTHRESH2_STEP3_15 0x0F + + +// RegAgcThresh3 - not present on RFM69/SX1231 +#define RF_AGCTHRESH3_STEP4_0 0x00 +#define RF_AGCTHRESH3_STEP4_1 0x10 +#define RF_AGCTHRESH3_STEP4_2 0x20 +#define RF_AGCTHRESH3_STEP4_3 0x30 +#define RF_AGCTHRESH3_STEP4_4 0x40 +#define RF_AGCTHRESH3_STEP4_5 0x50 +#define RF_AGCTHRESH3_STEP4_6 0x60 +#define RF_AGCTHRESH3_STEP4_7 0x70 +#define RF_AGCTHRESH3_STEP4_8 0x80 +#define RF_AGCTHRESH3_STEP4_9 0x90 // Default +#define RF_AGCTHRESH3_STEP4_10 0xA0 +#define RF_AGCTHRESH3_STEP4_11 0xB0 +#define RF_AGCTHRESH3_STEP4_12 0xC0 +#define RF_AGCTHRESH3_STEP4_13 0xD0 +#define RF_AGCTHRESH3_STEP4_14 0xE0 +#define RF_AGCTHRESH3_STEP4_15 0xF0 + +#define RF_AGCTHRESH3_STEP5_0 0x00 +#define RF_AGCTHRESH3_STEP5_1 0x01 +#define RF_AGCTHRESH3_STEP5_2 0x02 +#define RF_AGCTHRESH3_STEP5_3 0x03 +#define RF_AGCTHRESH3_STEP5_4 0x04 +#define RF_AGCTHRESH3_STEP5_5 0x05 +#define RF_AGCTHRESH3_STEP5_6 0x06 +#define RF_AGCTHRESH3_STEP5_7 0x07 +#define RF_AGCTHRES33_STEP5_8 0x08 +#define RF_AGCTHRESH3_STEP5_9 0x09 +#define RF_AGCTHRESH3_STEP5_10 0x0A +#define RF_AGCTHRESH3_STEP5_11 0x0B // Default +#define RF_AGCTHRESH3_STEP5_12 0x0C +#define RF_AGCTHRESH3_STEP5_13 0x0D +#define RF_AGCTHRESH3_STEP5_14 0x0E +#define RF_AGCTHRESH3_STEP5_15 0x0F + + +// RegLna +#define RF_LNA_ZIN_50 0x00 // Reset value +#define RF_LNA_ZIN_200 0x80 // Recommended default + +#define RF_LNA_LOWPOWER_OFF 0x00 // Default +#define RF_LNA_LOWPOWER_ON 0x40 + +#define RF_LNA_CURRENTGAIN 0x08 + +#define RF_LNA_GAINSELECT_AUTO 0x00 // Default +#define RF_LNA_GAINSELECT_MAX 0x01 +#define RF_LNA_GAINSELECT_MAXMINUS6 0x02 +#define RF_LNA_GAINSELECT_MAXMINUS12 0x03 +#define RF_LNA_GAINSELECT_MAXMINUS24 0x04 +#define RF_LNA_GAINSELECT_MAXMINUS36 0x05 +#define RF_LNA_GAINSELECT_MAXMINUS48 0x06 + + +// RegRxBw +#define RF_RXBW_DCCFREQ_000 0x00 +#define RF_RXBW_DCCFREQ_001 0x20 +#define RF_RXBW_DCCFREQ_010 0x40 // Recommended default +#define RF_RXBW_DCCFREQ_011 0x60 +#define RF_RXBW_DCCFREQ_100 0x80 // Reset value +#define RF_RXBW_DCCFREQ_101 0xA0 +#define RF_RXBW_DCCFREQ_110 0xC0 +#define RF_RXBW_DCCFREQ_111 0xE0 + +#define RF_RXBW_MANT_16 0x00 // Reset value +#define RF_RXBW_MANT_20 0x08 +#define RF_RXBW_MANT_24 0x10 // Recommended default + +#define RF_RXBW_EXP_0 0x00 +#define RF_RXBW_EXP_1 0x01 +#define RF_RXBW_EXP_2 0x02 +#define RF_RXBW_EXP_3 0x03 +#define RF_RXBW_EXP_4 0x04 +#define RF_RXBW_EXP_5 0x05 // Recommended default +#define RF_RXBW_EXP_6 0x06 // Reset value +#define RF_RXBW_EXP_7 0x07 + + +// RegAfcBw +#define RF_AFCBW_DCCFREQAFC_000 0x00 +#define RF_AFCBW_DCCFREQAFC_001 0x20 +#define RF_AFCBW_DCCFREQAFC_010 0x40 +#define RF_AFCBW_DCCFREQAFC_011 0x60 +#define RF_AFCBW_DCCFREQAFC_100 0x80 // Default +#define RF_AFCBW_DCCFREQAFC_101 0xA0 +#define RF_AFCBW_DCCFREQAFC_110 0xC0 +#define RF_AFCBW_DCCFREQAFC_111 0xE0 + +#define RF_AFCBW_MANTAFC_16 0x00 +#define RF_AFCBW_MANTAFC_20 0x08 // Default +#define RF_AFCBW_MANTAFC_24 0x10 + +#define RF_AFCBW_EXPAFC_0 0x00 +#define RF_AFCBW_EXPAFC_1 0x01 +#define RF_AFCBW_EXPAFC_2 0x02 // Reset value +#define RF_AFCBW_EXPAFC_3 0x03 // Recommended default +#define RF_AFCBW_EXPAFC_4 0x04 +#define RF_AFCBW_EXPAFC_5 0x05 +#define RF_AFCBW_EXPAFC_6 0x06 +#define RF_AFCBW_EXPAFC_7 0x07 + + +// RegOokPeak +#define RF_OOKPEAK_THRESHTYPE_FIXED 0x00 +#define RF_OOKPEAK_THRESHTYPE_PEAK 0x40 // Default +#define RF_OOKPEAK_THRESHTYPE_AVERAGE 0x80 + +#define RF_OOKPEAK_PEAKTHRESHSTEP_000 0x00 // Default +#define RF_OOKPEAK_PEAKTHRESHSTEP_001 0x08 +#define RF_OOKPEAK_PEAKTHRESHSTEP_010 0x10 +#define RF_OOKPEAK_PEAKTHRESHSTEP_011 0x18 +#define RF_OOKPEAK_PEAKTHRESHSTEP_100 0x20 +#define RF_OOKPEAK_PEAKTHRESHSTEP_101 0x28 +#define RF_OOKPEAK_PEAKTHRESHSTEP_110 0x30 +#define RF_OOKPEAK_PEAKTHRESHSTEP_111 0x38 + +#define RF_OOKPEAK_PEAKTHRESHDEC_000 0x00 // Default +#define RF_OOKPEAK_PEAKTHRESHDEC_001 0x01 +#define RF_OOKPEAK_PEAKTHRESHDEC_010 0x02 +#define RF_OOKPEAK_PEAKTHRESHDEC_011 0x03 +#define RF_OOKPEAK_PEAKTHRESHDEC_100 0x04 +#define RF_OOKPEAK_PEAKTHRESHDEC_101 0x05 +#define RF_OOKPEAK_PEAKTHRESHDEC_110 0x06 +#define RF_OOKPEAK_PEAKTHRESHDEC_111 0x07 + + +// RegOokAvg +#define RF_OOKAVG_AVERAGETHRESHFILT_00 0x00 +#define RF_OOKAVG_AVERAGETHRESHFILT_01 0x40 +#define RF_OOKAVG_AVERAGETHRESHFILT_10 0x80 // Default +#define RF_OOKAVG_AVERAGETHRESHFILT_11 0xC0 + + +// RegOokFix +#define RF_OOKFIX_FIXEDTHRESH_VALUE 0x06 // Default + + +// RegAfcFei +#define RF_AFCFEI_FEI_DONE 0x40 +#define RF_AFCFEI_FEI_START 0x20 +#define RF_AFCFEI_AFC_DONE 0x10 +#define RF_AFCFEI_AFCAUTOCLEAR_ON 0x08 +#define RF_AFCFEI_AFCAUTOCLEAR_OFF 0x00 // Default + +#define RF_AFCFEI_AFCAUTO_ON 0x04 +#define RF_AFCFEI_AFCAUTO_OFF 0x00 // Default + +#define RF_AFCFEI_AFC_CLEAR 0x02 +#define RF_AFCFEI_AFC_START 0x01 + + +// RegRssiConfig +#define RF_RSSI_FASTRX_ON 0x08 // not present on RFM69/SX1231 +#define RF_RSSI_FASTRX_OFF 0x00 // Default + +#define RF_RSSI_DONE 0x02 +#define RF_RSSI_START 0x01 + + +// RegDioMapping1 +#define RF_DIOMAPPING1_DIO0_00 0x00 // Default +#define RF_DIOMAPPING1_DIO0_01 0x40 +#define RF_DIOMAPPING1_DIO0_10 0x80 +#define RF_DIOMAPPING1_DIO0_11 0xC0 + +#define RF_DIOMAPPING1_DIO1_00 0x00 // Default +#define RF_DIOMAPPING1_DIO1_01 0x10 +#define RF_DIOMAPPING1_DIO1_10 0x20 +#define RF_DIOMAPPING1_DIO1_11 0x30 + +#define RF_DIOMAPPING1_DIO2_00 0x00 // Default +#define RF_DIOMAPPING1_DIO2_01 0x04 +#define RF_DIOMAPPING1_DIO2_10 0x08 +#define RF_DIOMAPPING1_DIO2_11 0x0C + +#define RF_DIOMAPPING1_DIO3_00 0x00 // Default +#define RF_DIOMAPPING1_DIO3_01 0x01 +#define RF_DIOMAPPING1_DIO3_10 0x02 +#define RF_DIOMAPPING1_DIO3_11 0x03 + + +// RegDioMapping2 +#define RF_DIOMAPPING2_DIO4_00 0x00 // Default +#define RF_DIOMAPPING2_DIO4_01 0x40 +#define RF_DIOMAPPING2_DIO4_10 0x80 +#define RF_DIOMAPPING2_DIO4_11 0xC0 + +#define RF_DIOMAPPING2_DIO5_00 0x00 // Default +#define RF_DIOMAPPING2_DIO5_01 0x10 +#define RF_DIOMAPPING2_DIO5_10 0x20 +#define RF_DIOMAPPING2_DIO5_11 0x30 + +#define RF_DIOMAPPING2_CLKOUT_32 0x00 +#define RF_DIOMAPPING2_CLKOUT_16 0x01 +#define RF_DIOMAPPING2_CLKOUT_8 0x02 +#define RF_DIOMAPPING2_CLKOUT_4 0x03 +#define RF_DIOMAPPING2_CLKOUT_2 0x04 +#define RF_DIOMAPPING2_CLKOUT_1 0x05 // Reset value +#define RF_DIOMAPPING2_CLKOUT_RC 0x06 +#define RF_DIOMAPPING2_CLKOUT_OFF 0x07 // Recommended default + + +// RegIrqFlags1 +#define RF_IRQFLAGS1_MODEREADY 0x80 +#define RF_IRQFLAGS1_RXREADY 0x40 +#define RF_IRQFLAGS1_TXREADY 0x20 +#define RF_IRQFLAGS1_PLLLOCK 0x10 +#define RF_IRQFLAGS1_RSSI 0x08 +#define RF_IRQFLAGS1_TIMEOUT 0x04 +#define RF_IRQFLAGS1_AUTOMODE 0x02 +#define RF_IRQFLAGS1_SYNCADDRESSMATCH 0x01 + + +// RegIrqFlags2 +#define RF_IRQFLAGS2_FIFOFULL 0x80 +#define RF_IRQFLAGS2_FIFONOTEMPTY 0x40 +#define RF_IRQFLAGS2_FIFOLEVEL 0x20 +#define RF_IRQFLAGS2_FIFOOVERRUN 0x10 +#define RF_IRQFLAGS2_PACKETSENT 0x08 +#define RF_IRQFLAGS2_PAYLOADREADY 0x04 +#define RF_IRQFLAGS2_CRCOK 0x02 +#define RF_IRQFLAGS2_LOWBAT 0x01 // not present on RFM69/SX1231 + + +// RegRssiThresh +#define RF_RSSITHRESH_VALUE 0xE4 // Default + + +// RegRxTimeout1 +#define RF_RXTIMEOUT1_RXSTART_VALUE 0x00 // Default + + +// RegRxTimeout2 +#define RF_RXTIMEOUT2_RSSITHRESH_VALUE 0x00 // Default + + +// RegPreamble +#define RF_PREAMBLESIZE_MSB_VALUE 0x00 // Default +#define RF_PREAMBLESIZE_LSB_VALUE 0x03 // Default + + +// RegSyncConfig +#define RF_SYNC_ON 0x80 // Default +#define RF_SYNC_OFF 0x00 + +#define RF_SYNC_FIFOFILL_AUTO 0x00 // Default -- when sync interrupt occurs +#define RF_SYNC_FIFOFILL_MANUAL 0x40 + +#define RF_SYNC_SIZE_1 0x00 +#define RF_SYNC_SIZE_2 0x08 +#define RF_SYNC_SIZE_3 0x10 +#define RF_SYNC_SIZE_4 0x18 // Default +#define RF_SYNC_SIZE_5 0x20 +#define RF_SYNC_SIZE_6 0x28 +#define RF_SYNC_SIZE_7 0x30 +#define RF_SYNC_SIZE_8 0x38 + +#define RF_SYNC_TOL_0 0x00 // Default +#define RF_SYNC_TOL_1 0x01 +#define RF_SYNC_TOL_2 0x02 +#define RF_SYNC_TOL_3 0x03 +#define RF_SYNC_TOL_4 0x04 +#define RF_SYNC_TOL_5 0x05 +#define RF_SYNC_TOL_6 0x06 +#define RF_SYNC_TOL_7 0x07 + + +// RegSyncValue1-8 +#define RF_SYNC_BYTE1_VALUE 0x00 // Default +#define RF_SYNC_BYTE2_VALUE 0x00 // Default +#define RF_SYNC_BYTE3_VALUE 0x00 // Default +#define RF_SYNC_BYTE4_VALUE 0x00 // Default +#define RF_SYNC_BYTE5_VALUE 0x00 // Default +#define RF_SYNC_BYTE6_VALUE 0x00 // Default +#define RF_SYNC_BYTE7_VALUE 0x00 // Default +#define RF_SYNC_BYTE8_VALUE 0x00 // Default + + +// RegPacketConfig1 +#define RF_PACKET1_FORMAT_FIXED 0x00 // Default +#define RF_PACKET1_FORMAT_VARIABLE 0x80 + +#define RF_PACKET1_DCFREE_OFF 0x00 // Default +#define RF_PACKET1_DCFREE_MANCHESTER 0x20 +#define RF_PACKET1_DCFREE_WHITENING 0x40 + +#define RF_PACKET1_CRC_ON 0x10 // Default +#define RF_PACKET1_CRC_OFF 0x00 + +#define RF_PACKET1_CRCAUTOCLEAR_ON 0x00 // Default +#define RF_PACKET1_CRCAUTOCLEAR_OFF 0x08 + +#define RF_PACKET1_ADRSFILTERING_OFF 0x00 // Default +#define RF_PACKET1_ADRSFILTERING_NODE 0x02 +#define RF_PACKET1_ADRSFILTERING_NODEBROADCAST 0x04 + + +// RegPayloadLength +#define RF_PAYLOADLENGTH_VALUE 0x40 // Default + + +// RegBroadcastAdrs +#define RF_BROADCASTADDRESS_VALUE 0x00 + + +// RegAutoModes +#define RF_AUTOMODES_ENTER_OFF 0x00 // Default +#define RF_AUTOMODES_ENTER_FIFONOTEMPTY 0x20 +#define RF_AUTOMODES_ENTER_FIFOLEVEL 0x40 +#define RF_AUTOMODES_ENTER_CRCOK 0x60 +#define RF_AUTOMODES_ENTER_PAYLOADREADY 0x80 +#define RF_AUTOMODES_ENTER_SYNCADRSMATCH 0xA0 +#define RF_AUTOMODES_ENTER_PACKETSENT 0xC0 +#define RF_AUTOMODES_ENTER_FIFOEMPTY 0xE0 + +#define RF_AUTOMODES_EXIT_OFF 0x00 // Default +#define RF_AUTOMODES_EXIT_FIFOEMPTY 0x04 +#define RF_AUTOMODES_EXIT_FIFOLEVEL 0x08 +#define RF_AUTOMODES_EXIT_CRCOK 0x0C +#define RF_AUTOMODES_EXIT_PAYLOADREADY 0x10 +#define RF_AUTOMODES_EXIT_SYNCADRSMATCH 0x14 +#define RF_AUTOMODES_EXIT_PACKETSENT 0x18 +#define RF_AUTOMODES_EXIT_RXTIMEOUT 0x1C + +#define RF_AUTOMODES_INTERMEDIATE_SLEEP 0x00 // Default +#define RF_AUTOMODES_INTERMEDIATE_STANDBY 0x01 +#define RF_AUTOMODES_INTERMEDIATE_RECEIVER 0x02 +#define RF_AUTOMODES_INTERMEDIATE_TRANSMITTER 0x03 + + +// RegFifoThresh +#define RF_FIFOTHRESH_TXSTART_FIFOTHRESH 0x00 // Reset value +#define RF_FIFOTHRESH_TXSTART_FIFONOTEMPTY 0x80 // Recommended default + +#define RF_FIFOTHRESH_VALUE 0x0F // Default + + +// RegPacketConfig2 +#define RF_PACKET2_RXRESTARTDELAY_1BIT 0x00 // Default +#define RF_PACKET2_RXRESTARTDELAY_2BITS 0x10 +#define RF_PACKET2_RXRESTARTDELAY_4BITS 0x20 +#define RF_PACKET2_RXRESTARTDELAY_8BITS 0x30 +#define RF_PACKET2_RXRESTARTDELAY_16BITS 0x40 +#define RF_PACKET2_RXRESTARTDELAY_32BITS 0x50 +#define RF_PACKET2_RXRESTARTDELAY_64BITS 0x60 +#define RF_PACKET2_RXRESTARTDELAY_128BITS 0x70 +#define RF_PACKET2_RXRESTARTDELAY_256BITS 0x80 +#define RF_PACKET2_RXRESTARTDELAY_512BITS 0x90 +#define RF_PACKET2_RXRESTARTDELAY_1024BITS 0xA0 +#define RF_PACKET2_RXRESTARTDELAY_2048BITS 0xB0 +#define RF_PACKET2_RXRESTARTDELAY_NONE 0xC0 +#define RF_PACKET2_RXRESTART 0x04 + +#define RF_PACKET2_AUTORXRESTART_ON 0x02 // Default +#define RF_PACKET2_AUTORXRESTART_OFF 0x00 + +#define RF_PACKET2_AES_ON 0x01 +#define RF_PACKET2_AES_OFF 0x00 // Default + + +// RegAesKey1-16 +#define RF_AESKEY1_VALUE 0x00 // Default +#define RF_AESKEY2_VALUE 0x00 // Default +#define RF_AESKEY3_VALUE 0x00 // Default +#define RF_AESKEY4_VALUE 0x00 // Default +#define RF_AESKEY5_VALUE 0x00 // Default +#define RF_AESKEY6_VALUE 0x00 // Default +#define RF_AESKEY7_VALUE 0x00 // Default +#define RF_AESKEY8_VALUE 0x00 // Default +#define RF_AESKEY9_VALUE 0x00 // Default +#define RF_AESKEY10_VALUE 0x00 // Default +#define RF_AESKEY11_VALUE 0x00 // Default +#define RF_AESKEY12_VALUE 0x00 // Default +#define RF_AESKEY13_VALUE 0x00 // Default +#define RF_AESKEY14_VALUE 0x00 // Default +#define RF_AESKEY15_VALUE 0x00 // Default +#define RF_AESKEY16_VALUE 0x00 // Default + + +// RegTemp1 +#define RF_TEMP1_MEAS_START 0x08 +#define RF_TEMP1_MEAS_RUNNING 0x04 +// not present on RFM69/SX1231 +#define RF_TEMP1_ADCLOWPOWER_ON 0x01 // Default +#define RF_TEMP1_ADCLOWPOWER_OFF 0x00 + + +// RegTestLna +#define RF_TESTLNA_NORMAL 0x1B +#define RF_TESTLNA_HIGH_SENSITIVITY 0x2D + + +// RegTestDagc +#define RF_DAGC_NORMAL 0x00 // Reset value +#define RF_DAGC_IMPROVED_LOWBETA1 0x20 +#define RF_DAGC_IMPROVED_LOWBETA0 0x30 // Recommended default
diff -r 000000000000 -r 80950b84a6c4 main.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/main.cpp Wed Jul 24 20:04:55 2019 +0000 @@ -0,0 +1,370 @@ +#include "mbed.h" +#include "stats_report.h" +/* User libraries */ +#include "definitions.h" +#include "reardefs.h" +#include "CANMsg.h" +#include "RFM69.h" + +#define MB1 // uncomment this line if MB1 +//#define MB2 // uncomment this line if MB2 + +#ifdef MB1 + #define NODE_ID MB1_ID +#endif +#ifdef MB2 + #define NODE_ID MB2_ID +#endif + +/* Communication protocols */ +CAN can(PB_8, PB_9, 1000000); +Serial serial(PA_2, PA_3, 115200); +RFM69 radio(PB_15, PB_14, PB_13, PB_12, PA_8); // RFM69::RFM69(PinName PinName mosi, PinName miso, PinName sclk,slaveSelectPin, PinName int) +/* I/O pins */ +AnalogIn analog(PA_0); +#ifdef MB1 +DigitalIn fuel_sensor(PB_5, PullNone); // MB2 +InterruptIn freq_sensor(PB_4, PullNone); // MB2 +#endif +#ifdef MB2 +DigitalIn fuel_sensor(PB_6, PullNone); // MB2 +InterruptIn freq_sensor(PB_5, PullNone); // MB2 +#endif +PwmOut servo(PA_6); +/* Debug pins */ +PwmOut signal(PA_7); +DigitalOut led(PC_13); +DigitalOut dbg1(PC_14); +DigitalOut dbg2(PC_15); +DigitalOut dbg3(PA_1); +DigitalOut dbg4(PA_4); +/* Interrupt services routine */ +void canISR(); +void servoSwitchISR(); +void ticker1HzISR(); +void ticker5HzISR(); +void ticker100HzISR(); +void frequencyCounterISR(); +/* Interrupt handlers */ +void canHandler(); +/* General functions*/ +void initPWM(); +void initRadio(); +void setupInterrupts(); +void filterMessage(CANMsg msg); +void writeServo(uint8_t state); + +/* Debug variables */ +Timer t; +Timer engine_counter; +bool buffer_full = false; +uint32_t tim1, tim2, imu_last_acq = 0; + +/* Mbed OS tools */ +Thread eventThread; +EventQueue queue(1024); +Ticker ticker1Hz; +Ticker ticker5Hz; +Ticker ticker100Hz; +Timeout fuel_timeout; +CircularBuffer <state_t, 2*BUFFER_SIZE> state_buffer; +CircularBuffer <imu_t*, 20> imu_buffer; + +/* Global variables */ +bool switch_clicked = false; +uint8_t switch_state = 0x00; +state_t current_state = IDLE_ST; +uint8_t pulse_counter = 0; +uint64_t current_period = 0, last_count = 0; +float rpm_hz, V_termistor = 0; +uint8_t fuel_timer = 0; +uint8_t fuel_counter = 0; +bool box = false; +packet_t data; // Create package for radio comunication +uint8_t imu_counter; + +int main() +{ + /* Main variables */ + CANMsg txMsg; + /* Initialization */ + t.start(); + eventThread.start(callback(&queue, &EventQueue::dispatch_forever)); + initPWM(); + initRadio(); + setupInterrupts(); + + while (true) { + if (state_buffer.full()) + { + buffer_full = true; + led = 0; + } + else + { + led = 1; + buffer_full = false; + if (!state_buffer.empty()) + state_buffer.pop(current_state); + else + current_state = IDLE_ST; + } + + switch (current_state) + { + case IDLE_ST: +// Thread::wait(1); + break; + case TEMP_ST: + //serial.printf("t"); + dbg1 = 0; + V_termistor = VCC*analog.read(); + data.temperature = ((float) (1.0/0.032)*log((1842.8*(VCC - V_termistor)/(V_termistor*R_TERM)))); + /* Send temperature data */ + txMsg.clear(TEMPERATURE_ID); + txMsg << data.temperature; + can.write(txMsg); + break; + case FUEL_ST: + //serial.printf("f"); + data.flags &= ~(0x88); // clear fuel and box flags + data.flags |= (fuel_counter > NORMAL_THRESHOLD) ? (0x01 << 3) : 0; + data.flags |= box << 7; + + txMsg.clear(FLAGS_ID); + txMsg << data.flags; + can.write(txMsg); + + fuel_timer = 0; + fuel_counter = 0; + ticker100Hz.attach(&ticker100HzISR, 0.01); + dbg1 = 0; + break; + case RPM_ST: + //serial.printf("r"); + dbg2 = 1; + freq_sensor.fall(NULL); // disable interrupt + if (current_period != 0) + { + rpm_hz = ((float)pulse_counter/(current_period/1000000.0)); //calculates frequency in Hz + if (switch_state != RUN_MODE) + writeServo(RUN_MODE); +// engine_counter.start(); + } + else + { + rpm_hz = 0; + writeServo(switch_state); +// engine_counter.stop(); + } + /* Send rpm data */ + txMsg.clear(RPM_ID); + txMsg << ((uint16_t) rpm_hz); + can.write(txMsg); + /* prepare to re-init rpm counter */ + pulse_counter = 0; + current_period = 0; // reset pulses related variables + last_count = t.read_us(); + freq_sensor.fall(&frequencyCounterISR); // enable interrupt + + dbg2 = 0; + break; + case THROTTLE_ST: + if (switch_clicked) + { + writeServo(switch_state); + switch_clicked = false; + } + + break; + case RADIO_ST: + imu_t* temp_imu; +// dbg4 = 1; + //if(radio.receiveDone()) +// { +// if (radio.ACKRequested()) +// radio.sendACK(); +// led = 0; +// box = (bool) radio.DATA; +//// serial.printf("%d\r\n", (bool)radio.DATA); +// } + +// serial.printf("%d,%d,%d\r\n", (!imu_buffer.empty()), (!d10hz_buffer.empty()), (!temp_buffer.empty())); +// if((!imu_buffer.empty()) && (!d10hz_buffer.empty()) && (!temp_buffer.empty())) +// { + if (!imu_buffer.empty()) + { + imu_buffer.pop(temp_imu); + memcpy(&data.imu, temp_imu, 4*sizeof(imu_t)); + data.rpm = ((uint16_t)rpm_hz * 60)*65536.0/5000.0; + radio.send((uint8_t)BOXRADIO_ID, &data, sizeof(packet_t), true, false); // request ACK with 1 retry (waitTime = 40ms) + } + else if (t.read_ms() - imu_last_acq > 500) + { + memset(&data.imu, 0, 4*sizeof(imu_t)); + data.rpm = ((uint16_t)rpm_hz * 60)*65536.0/5000.0; + radio.send((uint8_t)BOXRADIO_ID, &data, sizeof(packet_t), true, false); // request ACK with 1 retry (waitTime = 40ms) + } +// } +// radio.receiveDone(); + dbg4 = 0; +// tim2 = t.read_us() - tim1; +// serial.printf("%d\r\n",tim2); + break; + case DEBUG_ST: +// serial.printf("radio state pushed"); +// serial.printf("bf=%d, cr=%d\r\n", buffer_full, switch_state); +// serial.printf("speed=%d\r\n", data.data_10hz[packet_counter[N_SPEED]].speed); +// serial.printf("rpm=%d\r\n", data.data_10hz[packet_counter[N_RPM]].rpm); +// serial.printf("imu acc x =%d\r\n", data.imu[imu_counter].acc_x); +// serial.printf("imu acc y =%d\r\n", data.imu[imu_counter].acc_y); +// serial.printf("imu acc z =%d\r\n", data.imu[imu_counter].acc_z); +// serial.printf("imu dps x =%d\r\n", data.imu[imu_counter].dps_x); +// serial.printf("imu dps y =%d\r\n", data.imu[imu_counter].dps_y); +// serial.printf("imu dps z =%d\r\n", data.imu[imu_counter].dps_z); + break; + default: + break; + } + } +} + +/* Interrupt services routine */ +void canISR() +{ + CAN_IER &= ~CAN_IER_FMPIE0; // disable RX interrupt + queue.call(&canHandler); // add canHandler() to events queue +} + +void ticker1HzISR() +{ + state_buffer.push(TEMP_ST); +} + +void ticker5HzISR() +{ + state_buffer.push(RPM_ST); + state_buffer.push(RADIO_ST); +} + +void ticker100HzISR() +{ + if (fuel_timer < 100) + { + fuel_timer++; + fuel_counter += !fuel_sensor.read(); + } + else + { + state_buffer.push(FUEL_ST); + ticker100Hz.detach(); + } +} + +void frequencyCounterISR() +{ + led = !led; + pulse_counter++; + current_period += t.read_us() - last_count; + last_count = t.read_us(); +} + +/* Interrupt handlers */ +void canHandler() +{ + CANMsg rxMsg; + + can.read(rxMsg); + filterMessage(rxMsg); + CAN_IER |= CAN_IER_FMPIE0; // enable RX interrupt +} + +/* General functions */ +void initPWM() +{ + servo.period_ms(20); // set signal frequency to 50Hz + servo.write(0); // disables servo + signal.period_ms(32); // set signal frequency to 1/0.032Hz + signal.write(0.5f); // dutycycle 50% +} + +void initRadio() +{ + radio.initialize(FREQUENCY_915MHZ, NODE_ID, NETWORK_ID); + radio.encrypt(0); + radio.setPowerLevel(20); +} + +void setupInterrupts() +{ + can.attach(&canISR, CAN::RxIrq); + ticker1Hz.attach(&ticker1HzISR, 1.0); + ticker5Hz.attach(&ticker5HzISR, 0.2); + ticker100Hz.attach(&ticker100HzISR, 0.01); + freq_sensor.fall(&frequencyCounterISR); +} + +void filterMessage(CANMsg msg) +{ + led = !led; + + if (msg.id == THROTTLE_ID) + { + switch_clicked = true; + state_buffer.push(THROTTLE_ST); + msg >> switch_state; + } + else if (msg.id == IMU_ACC_ID) + { + imu_last_acq = t.read_ms(); + msg >> data.imu[imu_counter].acc_x >> data.imu[imu_counter].acc_y >> data.imu[imu_counter].acc_z; + } + else if (msg.id == IMU_DPS_ID) + { + msg >> data.imu[imu_counter].dps_x >> data.imu[imu_counter].dps_y + >> data.imu[imu_counter].dps_z; + if (imu_counter < 3) + { + imu_counter++; + } + else if (imu_counter == 3) + { + imu_buffer.push(data.imu); + imu_counter = 0; + } + } + else if (msg.id == SPEED_ID) + { + msg >> data.speed; +// serial.printf("\r\nspeed = %d\r\n",data.data_10hz[packet_counter[N_SPEED]].speed); +// d10hz_buffer.push(data.data_10hz); + } +} + + void writeServo(uint8_t state) +{ + data.flags &= ~(0x07); // reset servo-related flags + + switch (state) + { + case MID_MODE: + dbg3 = !dbg3; + servo.pulsewidth_us(SERVO_MID); + data.flags &= ~(0x03); // reset run and choke flags + break; + case RUN_MODE: + dbg3 = !dbg3; + servo.pulsewidth_us(SERVO_RUN); + data.flags |= RUN_MODE; // set run flag + break; + case CHOKE_MODE: + dbg3 = !dbg3; + servo.pulsewidth_us(SERVO_CHOKE); + data.flags |= CHOKE_MODE; // set choke flag + break; + default: +// serial.printf("Choke/run error\r\n"); + data.flags |= 0x04; // set servo error flag + break; + } +}
diff -r 000000000000 -r 80950b84a6c4 mbed-os.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-os.lib Wed Jul 24 20:04:55 2019 +0000 @@ -0,0 +1,1 @@ +https://github.com/ARMmbed/mbed-os/#51d55508e8400b60af467005646c4e2164738d48
diff -r 000000000000 -r 80950b84a6c4 reardefs.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/reardefs.h Wed Jul 24 20:04:55 2019 +0000 @@ -0,0 +1,32 @@ +#ifndef REARDEFS_H +#define REARDEFS_H + +#define SERVO_RUN 866 +#define RUN_MODE 0x01 +#define SERVO_MID 1320 +#define MID_MODE 0x00 +#define SERVO_CHOKE 1780 +#define CHOKE_MODE 0x02 +#define VCC 3.3 +#define R_TERM 1000 + +/* Radio definitions */ +#define NETWORK_ID 101 +#define BOXRADIO_ID 69 +#define MB1_ID 41 +#define MB2_ID 55 +#define FREQUENCY_915MHZ 91 +#define NORMAL_THRESHOLD 68 + +typedef enum +{ + IDLE_ST, // wait + TEMP_ST, // measure temperatures + FUEL_ST, // proccess fuel data sampling + RPM_ST, // calculate speed + THROTTLE_ST, // write throttle position (PWM) + RADIO_ST, // send data for box via radio (SPI) + DEBUG_ST // send data for debug +} state_t; + +#endif