Add some code that does nothing
This commit is contained in:
parent
ad7126362e
commit
5f0cf28755
@ -20,8 +20,9 @@ add_compile_definitions(
|
||||
STM32F1
|
||||
STM32F103C8T6
|
||||
DEBUG
|
||||
TARGETS=stm32/f1
|
||||
)
|
||||
add_executable(lora src/main.c)
|
||||
add_executable(lora src/main.c src/sx1276.c src/util.c include/util.h)
|
||||
|
||||
set_target_properties(lora PROPERTIES SUFFIX .elf)
|
||||
|
||||
@ -33,5 +34,5 @@ add_subdirectory(RTT)
|
||||
target_link_libraries(lora PUBLIC RTT)
|
||||
|
||||
target_include_directories(lora PUBLIC
|
||||
RTT ${LIBOPENCM3_DIR}/include
|
||||
RTT ${LIBOPENCM3_DIR}/include include
|
||||
)
|
||||
|
@ -87,7 +87,7 @@ Revision: $Rev: 21386 $
|
||||
#endif
|
||||
|
||||
#ifndef BUFFER_SIZE_UP
|
||||
#define BUFFER_SIZE_UP (256) // Size of the buffer for terminal output of target, up to host (Default: 1k)
|
||||
#define BUFFER_SIZE_UP (1024) // Size of the buffer for terminal output of target, up to host (Default: 1k)
|
||||
#endif
|
||||
|
||||
#ifndef BUFFER_SIZE_DOWN
|
||||
|
143
include/delay.h
Normal file
143
include/delay.h
Normal file
@ -0,0 +1,143 @@
|
||||
/*
|
||||
* This file is part of the HAL project, inline library above libopencm3.
|
||||
*
|
||||
* This library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU Lesser General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This library 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 Lesser General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU Lesser General Public License
|
||||
* along with this library. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/** @defgroup DELAY_module DELAY module
|
||||
*
|
||||
* @brief Spin-waiting blocking API
|
||||
*
|
||||
* @ingroup modules
|
||||
*
|
||||
* LGPL License Terms @ref lgpl_license
|
||||
*/
|
||||
#ifndef HAL_DELAY_H_INCLUDED
|
||||
#define HAL_DELAY_H_INCLUDED
|
||||
|
||||
#include <libopencm3/cm3/common.h>
|
||||
#include <libopencm3/stm32/rcc.h>
|
||||
|
||||
/**@{*/
|
||||
|
||||
/*****************************************************************************/
|
||||
/* API definitions */
|
||||
/*****************************************************************************/
|
||||
|
||||
/*****************************************************************************/
|
||||
/* API Functions */
|
||||
/*****************************************************************************/
|
||||
|
||||
BEGIN_DECLS
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** @brief Spin-wait delay, spinning specified amount of processor cycles
|
||||
*
|
||||
* @note this function can be used for delays of max 2500000 cycles.
|
||||
* For larger delays, please consider using timers or other waiting techniques.
|
||||
*
|
||||
* @param[in] cycles Cycles count need to spent in spin-wait
|
||||
*/
|
||||
static void delay_cycles(const int64_t cycles);
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** @brief Spin-wait delay, spinning specified amount of microseconds
|
||||
*
|
||||
* @note this function can be used for delays max 25 sec @ 168MHz CPU clock, or
|
||||
* max 525 sec @ 8MHz CPU clock! For larger delays, please consider using
|
||||
* timers or other waiting techniques.
|
||||
*
|
||||
* @param[in] us Microseconds needed to spin wait.
|
||||
* @param[in] cpufreq Current CPU frequency in Hz
|
||||
*/
|
||||
static void delay_us(uint32_t us);
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** @brief Spin-wait delay, spinning specified amount of microseconds
|
||||
*
|
||||
* @note this function can be used for delays max 25 sec @ 168MHz CPU clock, or
|
||||
* max 525 sec @ 8MHz CPU clock! For larger delays, please consider using
|
||||
* timers or other waiting techniques.
|
||||
*
|
||||
* @param[in] ms Milliseconds needed to spin wait.
|
||||
* @param[in] cpufreq Current CPU frequency in Hz
|
||||
*/
|
||||
static void delay_ms(uint32_t ms);
|
||||
|
||||
END_DECLS
|
||||
|
||||
/**@}*/
|
||||
|
||||
/*****************************************************************************/
|
||||
/* Architecture dependent implementations */
|
||||
/*****************************************************************************/
|
||||
|
||||
static void _delay_3t(uint32_t cycles) __attribute__((naked));
|
||||
|
||||
/* 3 Tcyc per tick, 4Tcyc call/ret, 1Tcyc hidden reg assignment */
|
||||
static void _delay_3t(uint32_t cycles)
|
||||
{
|
||||
asm __volatile__ (
|
||||
".syntax unified\n"
|
||||
"1: \n"
|
||||
" subs %[cyc],#1 \n" /* 1Tck */
|
||||
" bne 1b \n" /* 2Tck */
|
||||
" bx lr \n"
|
||||
".syntax divided\n"
|
||||
: /* No output */
|
||||
: [cyc] "r" (cycles)
|
||||
: /* No memory */
|
||||
);
|
||||
}
|
||||
|
||||
|
||||
static inline __attribute__((always_inline)) void delay_cycles(const int64_t cycles)
|
||||
{
|
||||
if (cycles <= 0)
|
||||
return;
|
||||
|
||||
switch (cycles % 3) {
|
||||
default:
|
||||
case 0: break;
|
||||
case 1: asm __volatile__ ("nop"); break;
|
||||
case 2: asm __volatile__ ("nop\nnop"); break;
|
||||
}
|
||||
|
||||
if (cycles > 3)
|
||||
_delay_3t((uint32_t)(cycles / 3));
|
||||
else /* same delay as the function call */
|
||||
asm __volatile__ ("nop\nnop\nnop\nnop\nnop\nnop\n");
|
||||
}
|
||||
|
||||
|
||||
/* max 25 sec @ 168MHz! */
|
||||
/* max 525 sec @ 8MHz! */
|
||||
static inline __attribute__((always_inline)) void delay_us(uint32_t us)
|
||||
{
|
||||
if (us == 0)
|
||||
return;
|
||||
|
||||
delay_cycles(us * rcc_ahb_frequency / 1000000 - 6);
|
||||
}
|
||||
|
||||
/* max 25 sec @ 168MHz! */
|
||||
/* max 525 sec @ 8MHz! */
|
||||
static inline __attribute__((always_inline)) void delay_ms(uint32_t ms)
|
||||
{
|
||||
if (ms == 0)
|
||||
return;
|
||||
|
||||
delay_cycles(ms * rcc_ahb_frequency / 1000 - 6);
|
||||
}
|
||||
|
||||
#endif /* HAL_DELAY_H_INCLUDED */
|
83
include/sx1276.h
Normal file
83
include/sx1276.h
Normal file
@ -0,0 +1,83 @@
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#define SX1276_RESET_PORT GPIOB
|
||||
#define SX1276_RESET_PIN GPIO0
|
||||
#define SX1276_SPI SPI1
|
||||
#define SX1276_SS_PORT GPIOA
|
||||
#define SX1276_SS_PIN GPIO4
|
||||
|
||||
enum sx1276_reg {
|
||||
SX1276_REG_FIFO = 0x00, // FIFO read/write access
|
||||
SX1276_REG_OP_MODE = 0x01, // Operating mode & LoRa (1) / FSK (0) selection
|
||||
SX1276_REG_FRF_MSB = 0x06, // RF Carrier Frequency, Most Significant Bits
|
||||
SX1276_REG_FRF_MID = 0x07, // RF Carrier Frequency, Intermediate Bits
|
||||
SX1276_REG_FRF_LSB = 0x08, // RF Carrier Frequency, Least Significant Bits
|
||||
SX1276_REG_PA_CONFIG = 0x09, // PA selection and Output Power control
|
||||
SX1276_REG_PA_RAMP = 0x0a, // Control of PA ramp time, low phase noise PLL
|
||||
SX1276_REG_OCP = 0x0b, // Over Current Protection control
|
||||
SX1276_REG_LNA = 0x0c, // LNA settings
|
||||
SX1276_REG_FIFO_ADDR_PTR = 0x0d, // FIFO SPI pointer
|
||||
SX1276_REG_FIFO_TX_BASE_ADDR = 0x0e, // Start Tx data
|
||||
SX1276_REG_FIFO_RX_BASE_ADDR = 0x0f, // Start Rx data
|
||||
SX1276_REG_FIFO_RX_CURRENT_ADDR = 0x10, // Start address of last packet received
|
||||
SX1276_REG_IRQ_FLAGS = 0x12, // IRQ flags
|
||||
SX1276_REG_RX_NB_BYTES = 0x13, // Number of received bytes
|
||||
SX1276_REG_MODEM_STATUS = 0x18, // Live LoRa modem status
|
||||
SX1276_REG_PKT_SNR_VALUE = 0x19, // Espimation of last packet SNR
|
||||
SX1276_REG_PKT_RSSI_VALUE = 0x1a, // RSSI of last packet
|
||||
SX1276_REG_MODEM_CONFIG_1 = 0x1d, // Modem PHY config 1
|
||||
SX1276_REG_MODEM_CONFIG_2 = 0x1e, // Modem PHY config 2
|
||||
SX1276_REG_PREAMBLE_MSB = 0x20, // Size of preamble
|
||||
SX1276_REG_PREAMBLE_LSB = 0x21, // Size of preamble
|
||||
SX1276_REG_PAYLOAD_LENGTH = 0x22, // LoRa payload length
|
||||
SX1276_REG_MODEM_CONFIG_3 = 0x26, // Modem PHY config 3
|
||||
SX1276_REG_RSSI_WIDEBAND = 0x2c, // Wideband RSSI measurement
|
||||
SX1276_REG_DETECTION_OPTIMIZE = 0x31, // LoRa detection Optimize for SF6
|
||||
SX1276_REG_DETECTION_THRESHOLD = 0x37, // LoRa detection threshold for SF6
|
||||
SX1276_REG_SYNC_WORD = 0x39, // LoRa Sync Word
|
||||
SX1276_REG_IRQ_FLAGS1 = 0x3e, // (FSK) Status register: PLL Lock state, Timeout, RSSI
|
||||
SX1276_REG_DIO_MAPPING_1 = 0x40, // Mapping of pins DIO0 to DIO3
|
||||
SX1276_REG_DIO_MAPPING_2 = 0x41, // Mapping of pins DIO4 and DIO5, ClkOut frequency
|
||||
SX1276_REG_VERSION = 0x42 // Semtech ID relating the silicon revision (0x12)
|
||||
};
|
||||
|
||||
enum sx1276_mode { // SX1276_REG_OP_MODE values
|
||||
SX1276_MODE_LONG_RANGE_MODE = 1<<7, // Set to enable LoRa mode
|
||||
SX1276_MODE_ACCESS_SHARED_REG = 1<<6, // Set to access FSK registers in 0x0D:0x3F while in LoRa mode
|
||||
SX1276_MODE_LOW_FREQUENCY_MODE = 1<<3, // Set to access Low Frequency Mode registers
|
||||
// 3 bits of LoRa Modes
|
||||
SX1276_MODE_SLEEP = 0x00, // FSK and LoRa modes can only be swiched in SLEEP
|
||||
SX1276_MODE_STDBY = 0x01,
|
||||
SX1276_MODE_FSTX = 0x02, // Frequency synthesis TX
|
||||
SX1276_MODE_TX = 0x03,
|
||||
SX1276_MODE_FSRX = 0x04, // Frequency synthesis RX
|
||||
SX1276_MODE_RX_CONTINUOUS = 0x05,
|
||||
SX1276_MODE_RX_SINGLE = 0x06,
|
||||
SX1276_MODE_CAD = 0x07 // Channel activity detection
|
||||
};
|
||||
|
||||
// PA config
|
||||
#define PA_BOOST 1<<7
|
||||
|
||||
// IRQ masks
|
||||
#define IRQ_TX_DONE_MASK 0x08
|
||||
#define IRQ_PAYLOAD_CRC_ERROR_MASK 0x20
|
||||
#define IRQ_RX_DONE_MASK 0x40
|
||||
|
||||
// FSK IRQ FLAGS
|
||||
#define IRQ_FLAGS1_MODE_READY 1<<7 // Set when the operation mode requested in Mode, is ready
|
||||
|
||||
#define FIFO_SIZE 0xff
|
||||
|
||||
struct sx1276_state_st {
|
||||
uint8_t fifo[FIFO_SIZE];
|
||||
};
|
||||
|
||||
uint8_t sx1276_read(uint8_t reg);
|
||||
uint8_t sx1276_write(uint8_t reg, uint8_t val);
|
||||
void sx1276_fifo_dump(struct sx1276_state_st *state);
|
||||
void sx1276_fifo_load(struct sx1276_state_st *state);
|
||||
void sx1276_fifo_write(uint8_t addr, uint8_t val);
|
||||
void sx1276_set_frequency(uint64_t frequency);
|
||||
struct sx1276_state_st *sx1276_init(uint64_t frequency);
|
8
include/util.h
Normal file
8
include/util.h
Normal file
@ -0,0 +1,8 @@
|
||||
#ifndef DHT_TEST_UTIL_H
|
||||
#define DHT_TEST_UTIL_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
void hexdump(char *buf, size_t size, uint32_t width);
|
||||
|
||||
#endif //DHT_TEST_UTIL_H
|
100
src/main.c
100
src/main.c
@ -1,29 +1,115 @@
|
||||
#include <libopencm3/stm32/rcc.h>
|
||||
#include <libopencm3/stm32/gpio.h>
|
||||
#include <libopencm3/stm32/spi.h>
|
||||
|
||||
#include <SEGGER_RTT.h>
|
||||
#include <sx1276.h>
|
||||
|
||||
#include "delay.h"
|
||||
#include "util.h"
|
||||
|
||||
uint8_t FIFO[FIFO_SIZE] = {0};
|
||||
|
||||
static void clock_setup(void)
|
||||
{
|
||||
rcc_clock_setup_pll(&rcc_hse_configs[RCC_CLOCK_HSE8_72MHZ]);
|
||||
|
||||
rcc_periph_clock_enable(RCC_GPIOA);
|
||||
rcc_periph_clock_enable(RCC_GPIOB);
|
||||
|
||||
rcc_periph_clock_enable(RCC_SPI1);
|
||||
}
|
||||
|
||||
static void gpio_setup(void)
|
||||
{
|
||||
rcc_periph_clock_enable(RCC_GPIOB);
|
||||
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, GPIO1);
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, GPIO0 | GPIO1);
|
||||
}
|
||||
|
||||
static void spi_setup(void)
|
||||
{
|
||||
/* Configure GPIOs: SS=PA4, SCK=PA5, MISO=PA6 and MOSI=PA7 */
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
|
||||
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL,
|
||||
GPIO5 | GPIO7 );
|
||||
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, GPIO4);
|
||||
gpio_set(GPIOA, GPIO4);
|
||||
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT,
|
||||
GPIO6);
|
||||
|
||||
/* Reset SPI, SPI_CR1 register cleared, SPI is disabled */
|
||||
spi_reset(SPI1);
|
||||
|
||||
|
||||
/* Set up SPI in Master mode with:
|
||||
* Clock baud rate: 1/64 of peripheral clock frequency
|
||||
* Clock polarity: Idle Low
|
||||
* Clock phase: Data valid on 1st clock pulse
|
||||
* Data frame format: 8-bit
|
||||
* Frame format: MSB First
|
||||
*/
|
||||
spi_init_master(SPI1, SPI_CR1_BAUDRATE_FPCLK_DIV_64,
|
||||
SPI_CR1_CPOL_CLK_TO_0_WHEN_IDLE,
|
||||
SPI_CR1_CPHA_CLK_TRANSITION_1, SPI_CR1_DFF_8BIT, SPI_CR1_MSBFIRST);
|
||||
|
||||
/*
|
||||
* Set NSS management to software.
|
||||
*
|
||||
* Note:
|
||||
* Setting nss high is very important, even if we are controlling the GPIO
|
||||
* ourselves this bit needs to be at least set to 1, otherwise the spi
|
||||
* peripheral will not send any data out.
|
||||
*/
|
||||
spi_enable_software_slave_management(SPI1);
|
||||
spi_set_nss_high(SPI1);
|
||||
|
||||
/* Enable SPI1 periph. */
|
||||
spi_enable(SPI1);
|
||||
}
|
||||
|
||||
int main(void)
|
||||
{
|
||||
int i;
|
||||
|
||||
clock_setup();
|
||||
spi_setup();
|
||||
gpio_setup();
|
||||
|
||||
SEGGER_RTT_WriteString(0, "SX1276 LoRa test\n");
|
||||
SEGGER_RTT_printf(0, "CPU clk: %dHz\n", rcc_ahb_frequency);
|
||||
|
||||
struct sx1276_state_st *sx1276_state = sx1276_init(86520000);
|
||||
|
||||
sx1276_fifo_write(0x0, 0xde);
|
||||
sx1276_fifo_write(0x1, 0xad);
|
||||
sx1276_fifo_write(0x2, 0xbe);
|
||||
sx1276_fifo_write(0x3, 0xef);
|
||||
|
||||
sx1276_write(SX1276_REG_PAYLOAD_LENGTH, 4);
|
||||
|
||||
sx1276_write(SX1276_REG_OP_MODE, SX1276_MODE_LONG_RANGE_MODE | SX1276_MODE_TX);
|
||||
|
||||
while (1) {
|
||||
int ret = sx1276_read(SX1276_REG_OP_MODE);
|
||||
SEGGER_RTT_printf(0, "MOD: 0x%02x ", ret);
|
||||
ret = sx1276_read(SX1276_REG_MODEM_STATUS);
|
||||
SEGGER_RTT_printf(0, "STAT: 0x%02x ", ret);
|
||||
ret = sx1276_read(SX1276_REG_IRQ_FLAGS);
|
||||
SEGGER_RTT_printf(0, "IRQ: 0x%02x\n", ret);
|
||||
if (ret & (1<<3)){
|
||||
break;
|
||||
}
|
||||
delay_ms(100);
|
||||
}
|
||||
SEGGER_RTT_printf(0, "Done\n");
|
||||
|
||||
|
||||
/* Blink the LED (PA5) on the board. */
|
||||
while (1) {
|
||||
|
||||
/* Using API function gpio_toggle(): */
|
||||
gpio_toggle(GPIOB, GPIO1); /* LED on/off */
|
||||
SEGGER_RTT_WriteString(0, "Hello World\n");
|
||||
for (i = 0; i < 800000; i++) /* Wait a bit. */
|
||||
__asm__("nop");
|
||||
delay_ms(500);
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
117
src/sx1276.c
Normal file
117
src/sx1276.c
Normal file
@ -0,0 +1,117 @@
|
||||
#include <libopencm3/stm32/gpio.h>
|
||||
#include <libopencm3/stm32/spi.h>
|
||||
|
||||
#include <SEGGER_RTT.h>
|
||||
#include "delay.h"
|
||||
#include "util.h"
|
||||
#include "sx1276.h"
|
||||
|
||||
|
||||
static uint8_t sx1276_spi_transaction(uint8_t reg, uint8_t val) {
|
||||
uint8_t ret;
|
||||
gpio_clear(SX1276_SS_PORT, SX1276_SS_PIN);
|
||||
spi_send(SX1276_SPI, reg);
|
||||
spi_read(SX1276_SPI);
|
||||
spi_send(SX1276_SPI, val);
|
||||
ret = spi_read(SX1276_SPI);
|
||||
gpio_set(SX1276_SS_PORT, SX1276_SS_PIN);
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint8_t sx1276_read(uint8_t reg) {
|
||||
reg &= 0x7f; // clear upper bit to make it read request
|
||||
return sx1276_spi_transaction(reg, 0x00);
|
||||
}
|
||||
|
||||
uint8_t sx1276_write(uint8_t reg, uint8_t val) {
|
||||
reg |= 0x80; // set upper bit to make it write request
|
||||
return sx1276_spi_transaction(reg, val);
|
||||
}
|
||||
|
||||
void sx1276_fifo_dump(struct sx1276_state_st *state) {
|
||||
sx1276_write(SX1276_REG_FIFO_ADDR_PTR, 0x00);
|
||||
gpio_clear(SX1276_SS_PORT, SX1276_SS_PIN);
|
||||
spi_send(SX1276_SPI, SX1276_REG_FIFO & 0x7f); // read
|
||||
spi_read(SX1276_SPI);
|
||||
for (int i=0; i < FIFO_SIZE; i++){
|
||||
spi_send(SX1276_SPI, 0x00);
|
||||
int val = spi_read(SX1276_SPI);
|
||||
state->fifo[i] = val;
|
||||
}
|
||||
gpio_set(GPIOA, GPIO4);
|
||||
}
|
||||
|
||||
void sx1276_fifo_load(struct sx1276_state_st *state) {
|
||||
sx1276_write(SX1276_REG_FIFO_ADDR_PTR, 0x00);
|
||||
gpio_clear(SX1276_SS_PORT, SX1276_SS_PIN);
|
||||
spi_send(SX1276_SPI, SX1276_REG_FIFO | 0x80); // write
|
||||
spi_read(SX1276_SPI);
|
||||
for (int i=0; i < FIFO_SIZE; i++){
|
||||
spi_send(SX1276_SPI, state->fifo[i]);
|
||||
spi_read(SX1276_SPI);
|
||||
}
|
||||
gpio_set(GPIOA, GPIO4);
|
||||
}
|
||||
|
||||
void sx1276_fifo_write(uint8_t addr, uint8_t val) {
|
||||
sx1276_write(SX1276_REG_FIFO_ADDR_PTR, addr);
|
||||
sx1276_write(SX1276_REG_FIFO, val);
|
||||
}
|
||||
|
||||
void sx1276_set_frequency(uint64_t frequency) {
|
||||
uint64_t frf = ((uint64_t)frequency << 19) / 32000000;
|
||||
|
||||
sx1276_write(SX1276_REG_FRF_MSB, (uint8_t)(frf >> 16));
|
||||
sx1276_write(SX1276_REG_FRF_MID, (uint8_t)(frf >> 8));
|
||||
sx1276_write(SX1276_REG_FRF_LSB, (uint8_t)(frf >> 0));
|
||||
}
|
||||
|
||||
struct sx1276_state_st *sx1276_init(uint64_t frequency) {
|
||||
struct sx1276_state_st *sx1276_state = (struct sx1276_state_st*) malloc(sizeof(struct sx1276_state_st));
|
||||
if (sx1276_state == NULL) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
SEGGER_RTT_printf(0, "SX1276: Reset\n");
|
||||
gpio_clear(GPIOB, GPIO0);
|
||||
delay_us(100);
|
||||
gpio_set(GPIOB, GPIO0);
|
||||
delay_ms(5);
|
||||
|
||||
uint8_t ret = sx1276_read(SX1276_REG_VERSION);
|
||||
// if (ret != 0x12) {
|
||||
// SEGGER_RTT_printf(0, "Invalid Chip Version, got: 0x%02x, expected: 0x12\n", ret);
|
||||
// //free(sx1276_state);
|
||||
// //return NULL;
|
||||
// }
|
||||
SEGGER_RTT_printf(0, "Chip Version: 0x%02X\n", ret);
|
||||
|
||||
uint8_t set = SX1276_MODE_LONG_RANGE_MODE | SX1276_MODE_SLEEP;
|
||||
ret = sx1276_write(SX1276_REG_OP_MODE, set);
|
||||
SEGGER_RTT_printf(0, "Going to LoRa SLEEP from: 0x%02X, to: 0x%02X\n",
|
||||
ret, set);
|
||||
|
||||
sx1276_set_frequency(frequency);
|
||||
|
||||
sx1276_write(SX1276_REG_FIFO_TX_BASE_ADDR, 0);
|
||||
sx1276_write(SX1276_REG_FIFO_RX_BASE_ADDR, 0);
|
||||
|
||||
sx1276_write(SX1276_REG_LNA, 0b11000000); // minimum strenght
|
||||
sx1276_write(SX1276_REG_PA_CONFIG, 1<<7); // minimum 2dBm
|
||||
|
||||
// Bw 7 125khz; CodingRate 1 4/5; implicit header mode
|
||||
sx1276_write(SX1276_REG_MODEM_CONFIG_1, (7 << 4) | (1 << 1) | 1);
|
||||
// SpreadingFactor 7 128 chips
|
||||
sx1276_write(SX1276_REG_MODEM_CONFIG_2, (7 << 4));
|
||||
|
||||
|
||||
set = SX1276_MODE_LONG_RANGE_MODE | SX1276_MODE_STDBY;
|
||||
ret = sx1276_write(SX1276_REG_OP_MODE, set);
|
||||
SEGGER_RTT_printf(0, "Going to LoRa STDBY from: 0x%02X, to: 0x%02x\n",
|
||||
ret, set);
|
||||
|
||||
|
||||
// We need to wait ~250us for TS_OSC to startup before we can access FIFO and some other things
|
||||
delay_us(250);
|
||||
return sx1276_state;
|
||||
};
|
17
src/util.c
Normal file
17
src/util.c
Normal file
@ -0,0 +1,17 @@
|
||||
#include <SEGGER_RTT.h>
|
||||
#include "util.h"
|
||||
|
||||
void hexdump(char *buf, size_t size, uint32_t width) {
|
||||
if (width == 0) {
|
||||
width = 16;
|
||||
}
|
||||
SEGGER_RTT_SetFlagsUpBuffer(0, SEGGER_RTT_MODE_BLOCK_IF_FIFO_FULL);
|
||||
for (unsigned int i = 0; i < size; i++) {
|
||||
SEGGER_RTT_printf(0, "%.2x ", buf[i]);
|
||||
if ((i+1) % width == 0) {
|
||||
SEGGER_RTT_printf(0,"\n");
|
||||
}
|
||||
}
|
||||
SEGGER_RTT_printf(0,"\n");
|
||||
SEGGER_RTT_SetFlagsUpBuffer(0, SEGGER_RTT_MODE_DEFAULT);
|
||||
}
|
Loading…
Reference in New Issue
Block a user