mirror of
https://github.com/peterantypas/maiana.git
synced 2025-05-27 21:00:24 -07:00
config and bsp for 10.5.0
This commit is contained in:
parent
a83a8dad98
commit
71672cf1bc
@ -27,7 +27,7 @@
|
||||
// Either modify this header or define a different symbol in the preprocessor to build for a different board
|
||||
|
||||
#ifndef BOARD_REV
|
||||
#define BOARD_REV 100
|
||||
#define BOARD_REV 105
|
||||
#endif
|
||||
|
||||
/**
|
||||
@ -91,6 +91,8 @@ bool bsp_read_station_data(StationData &data);
|
||||
#include <bsp_9_3.hpp>
|
||||
#elif BOARD_REV == 100
|
||||
#include <bsp_10_0.hpp>
|
||||
#elif BOARD_REV == 105
|
||||
#include <bsp_10_5.hpp>
|
||||
#endif
|
||||
|
||||
|
||||
|
95
latest/Firmware/Inc/bsp/bsp_10_5.hpp
Normal file
95
latest/Firmware/Inc/bsp/bsp_10_5.hpp
Normal file
@ -0,0 +1,95 @@
|
||||
/*
|
||||
Copyright (c) 2016-2020 Peter Antypas
|
||||
|
||||
This file is part of the MAIANA™ transponder firmware.
|
||||
|
||||
The firmware 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 <https://www.gnu.org/licenses/>
|
||||
*/
|
||||
|
||||
#ifndef INC_BSP_10_0_HPP_
|
||||
#define INC_BSP_10_0_HPP_
|
||||
|
||||
|
||||
|
||||
// GPIO Pin definitions
|
||||
#define GNSS_EN_PORT GPIOC
|
||||
#define GNSS_EN_PIN GPIO_PIN_14
|
||||
|
||||
#define TRX_IC_CLK_PORT GPIOC
|
||||
#define TRX_IC_CLK_PIN GPIO_PIN_15
|
||||
|
||||
#define CS2_PORT GPIOA
|
||||
#define CS2_PIN GPIO_PIN_0
|
||||
|
||||
#define RX_EVT_PORT GPIOA
|
||||
#define RX_EVT_PIN GPIO_PIN_1
|
||||
|
||||
#define GNSS_1PPS_PORT GPIOA
|
||||
#define GNSS_1PPS_PIN GPIO_PIN_2
|
||||
|
||||
#define GNSS_NMEA_RX_PORT GPIOA
|
||||
#define GNSS_NMEA_RX_PIN GPIO_PIN_3
|
||||
|
||||
#define CS1_PORT GPIOA
|
||||
#define CS1_PIN GPIO_PIN_4
|
||||
|
||||
#define SCK_PORT GPIOA
|
||||
#define SCK_PIN GPIO_PIN_5
|
||||
|
||||
#define MISO_PORT GPIOA
|
||||
#define MISO_PIN GPIO_PIN_6
|
||||
|
||||
#define MOSI_PORT GPIOA
|
||||
#define MOSI_PIN GPIO_PIN_7
|
||||
|
||||
#define SDN1_PORT GPIOB
|
||||
#define SDN1_PIN GPIO_PIN_0
|
||||
|
||||
#define TRX_IC_DATA_PORT GPIOB
|
||||
#define TRX_IC_DATA_PIN GPIO_PIN_1
|
||||
|
||||
#define TX_CTRL_PORT GPIOA
|
||||
#define TX_CTRL_PIN GPIO_PIN_8
|
||||
|
||||
#define UART_TX_PORT GPIOA
|
||||
#define UART_TX_PIN GPIO_PIN_9
|
||||
|
||||
#define UART_RX_PORT GPIOA
|
||||
#define UART_RX_PIN GPIO_PIN_10
|
||||
|
||||
#define GNSS_STATE_PORT GPIOA
|
||||
#define GNSS_STATE_PIN GPIO_PIN_11
|
||||
|
||||
#define TX_DISABLE_PORT GPIOA
|
||||
#define TX_DISABLE_PIN GPIO_PIN_12
|
||||
|
||||
#define SDN2_PORT GPIOA
|
||||
#define SDN2_PIN GPIO_PIN_15
|
||||
|
||||
#define RX_IC_CLK_PORT GPIOB
|
||||
#define RX_IC_CLK_PIN GPIO_PIN_3
|
||||
|
||||
#define RX_IC_DATA_PORT GPIOB
|
||||
#define RX_IC_DATA_PIN GPIO_PIN_4
|
||||
|
||||
#define TX_EVT_PORT GPIOB
|
||||
#define TX_EVT_PIN GPIO_PIN_5
|
||||
|
||||
#define RX_EN_PORT GPIOB
|
||||
#define RX_EN_PIN GPIO_PIN_6
|
||||
|
||||
|
||||
|
||||
|
||||
#endif /* INC_BSP_5_0_HPP_ */
|
@ -31,5 +31,6 @@
|
||||
|
||||
uint8_t* get_si4467_config_array();
|
||||
uint8_t* get_si4463_config_array();
|
||||
uint8_t* get_si4460_config_array();
|
||||
|
||||
#endif /* RADIO_CONFIG_H_ */
|
||||
|
632
latest/Firmware/Inc/radio_config_si4460.h
Normal file
632
latest/Firmware/Inc/radio_config_si4460.h
Normal file
@ -0,0 +1,632 @@
|
||||
/*! @file radio_config.h
|
||||
* @brief This file contains the automatically generated
|
||||
* configurations.
|
||||
*
|
||||
* @n WDS GUI Version: 3.2.11.0
|
||||
* @n Device: Si4460 Rev.: B1
|
||||
*
|
||||
* @b COPYRIGHT
|
||||
* @n Silicon Laboratories Confidential
|
||||
* @n Copyright 2017 Silicon Laboratories, Inc.
|
||||
* @n http://www.silabs.com
|
||||
*/
|
||||
|
||||
#ifndef RADIO_CONFIG_H_
|
||||
#define RADIO_CONFIG_H_
|
||||
|
||||
// USER DEFINED PARAMETERS
|
||||
// Define your own parameters here
|
||||
|
||||
// INPUT DATA
|
||||
/*
|
||||
// Crys_freq(Hz): 30000000 Crys_tol(ppm): 15 IF_mode: 2 High_perf_Ch_Fil: 1 OSRtune: 0 Ch_Fil_Bw_AFC: 0 ANT_DIV: 0 PM_pattern: 15
|
||||
// MOD_type: 3 Rsymb(sps): 9600 Fdev(Hz): 2400 RXBW(Hz): 150000 Manchester: 0 AFC_en: 0 Rsymb_error: 0.0 Chip-Version: 2
|
||||
// RF Freq.(MHz): 161.5 API_TC: 29 fhst: 25000 inputBW: 0 BERT: 0 RAW_dout: 0 D_source: 0 Hi_pfm_div: 1
|
||||
//
|
||||
// # RX IF frequency is -468750 Hz
|
||||
// # WB filter 3 (BW = 23.15 kHz); NB-filter 3 (BW = 23.15 kHz)
|
||||
//
|
||||
// Modulation index: 0.5
|
||||
*/
|
||||
|
||||
|
||||
// CONFIGURATION PARAMETERS
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_XO_FREQ 30000000L
|
||||
#define RADIO_CONFIGURATION_DATA_CHANNEL_NUMBER 0x00
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_PACKET_LENGTH 0x07
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_STATE_AFTER_POWER_UP 0x03
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_DELAY_CNT_AFTER_RESET 0xF000
|
||||
|
||||
|
||||
// CONFIGURATION COMMANDS
|
||||
|
||||
/*
|
||||
// Command: RF_POWER_UP
|
||||
// Description: Command to power-up the device and select the operational mode and functionality.
|
||||
*/
|
||||
#define RF_POWER_UP 0x02, 0x01, 0x00, 0x01, 0xC9, 0xC3, 0x80
|
||||
|
||||
/*
|
||||
// Command: RF_GPIO_PIN_CFG
|
||||
// Description: Configures the GPIO pins.
|
||||
*/
|
||||
#define RF_GPIO_PIN_CFG 0x13, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
|
||||
/*
|
||||
// Set properties: RF_GLOBAL_XO_TUNE_2
|
||||
// Number of properties: 2
|
||||
// Group ID: 0x00
|
||||
// Start ID: 0x00
|
||||
// Default values: 0x40, 0x00,
|
||||
// Descriptions:
|
||||
// GLOBAL_XO_TUNE - Configure the internal capacitor frequency tuning bank for the crystal oscillator.
|
||||
// GLOBAL_CLK_CFG - Clock configuration options.
|
||||
*/
|
||||
#define RF_GLOBAL_XO_TUNE_2 0x11, 0x00, 0x02, 0x00, 0x2D, 0x00
|
||||
|
||||
/*
|
||||
// Set properties: RF_GLOBAL_CONFIG_1
|
||||
// Number of properties: 1
|
||||
// Group ID: 0x00
|
||||
// Start ID: 0x03
|
||||
// Default values: 0x20,
|
||||
// Descriptions:
|
||||
// GLOBAL_CONFIG - Global configuration settings.
|
||||
*/
|
||||
#define RF_GLOBAL_CONFIG_1 0x11, 0x00, 0x01, 0x03, 0x60
|
||||
|
||||
/*
|
||||
// Set properties: RF_INT_CTL_ENABLE_1
|
||||
// Number of properties: 1
|
||||
// Group ID: 0x01
|
||||
// Start ID: 0x00
|
||||
// Default values: 0x04,
|
||||
// Descriptions:
|
||||
// INT_CTL_ENABLE - This property provides for global enabling of the three interrupt groups (Chip, Modem and Packet Handler) in order to generate HW interrupts at the NIRQ pin.
|
||||
*/
|
||||
#define RF_INT_CTL_ENABLE_1 0x11, 0x01, 0x01, 0x00, 0x00
|
||||
|
||||
/*
|
||||
// Set properties: RF_FRR_CTL_A_MODE_4
|
||||
// Number of properties: 4
|
||||
// Group ID: 0x02
|
||||
// Start ID: 0x00
|
||||
// Default values: 0x01, 0x02, 0x09, 0x00,
|
||||
// Descriptions:
|
||||
// FRR_CTL_A_MODE - Fast Response Register A Configuration.
|
||||
// FRR_CTL_B_MODE - Fast Response Register B Configuration.
|
||||
// FRR_CTL_C_MODE - Fast Response Register C Configuration.
|
||||
// FRR_CTL_D_MODE - Fast Response Register D Configuration.
|
||||
*/
|
||||
#define RF_FRR_CTL_A_MODE_4 0x11, 0x02, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
|
||||
/*
|
||||
// Set properties: RF_PREAMBLE_TX_LENGTH_9
|
||||
// Number of properties: 9
|
||||
// Group ID: 0x10
|
||||
// Start ID: 0x00
|
||||
// Default values: 0x08, 0x14, 0x00, 0x0F, 0x21, 0x00, 0x00, 0x00, 0x00,
|
||||
// Descriptions:
|
||||
// PREAMBLE_TX_LENGTH - Configure length of TX Preamble.
|
||||
// PREAMBLE_CONFIG_STD_1 - Configuration of reception of a packet with a Standard Preamble pattern.
|
||||
// PREAMBLE_CONFIG_NSTD - Configuration of transmission/reception of a packet with a Non-Standard Preamble pattern.
|
||||
// PREAMBLE_CONFIG_STD_2 - Configuration of timeout periods during reception of a packet with Standard Preamble pattern.
|
||||
// PREAMBLE_CONFIG - General configuration bits for the Preamble field.
|
||||
// PREAMBLE_PATTERN_31_24 - Configuration of the bit values describing a Non-Standard Preamble pattern.
|
||||
// PREAMBLE_PATTERN_23_16 - Configuration of the bit values describing a Non-Standard Preamble pattern.
|
||||
// PREAMBLE_PATTERN_15_8 - Configuration of the bit values describing a Non-Standard Preamble pattern.
|
||||
// PREAMBLE_PATTERN_7_0 - Configuration of the bit values describing a Non-Standard Preamble pattern.
|
||||
*/
|
||||
#define RF_PREAMBLE_TX_LENGTH_9 0x11, 0x10, 0x09, 0x00, 0x08, 0x14, 0x00, 0x0F, 0x31, 0x00, 0x00, 0x00, 0x00
|
||||
|
||||
/*
|
||||
// Set properties: RF_SYNC_CONFIG_5
|
||||
// Number of properties: 5
|
||||
// Group ID: 0x11
|
||||
// Start ID: 0x00
|
||||
// Default values: 0x01, 0x2D, 0xD4, 0x2D, 0xD4,
|
||||
// Descriptions:
|
||||
// SYNC_CONFIG - Sync Word configuration bits.
|
||||
// SYNC_BITS_31_24 - Sync word.
|
||||
// SYNC_BITS_23_16 - Sync word.
|
||||
// SYNC_BITS_15_8 - Sync word.
|
||||
// SYNC_BITS_7_0 - Sync word.
|
||||
*/
|
||||
#define RF_SYNC_CONFIG_5 0x11, 0x11, 0x05, 0x00, 0x01, 0xCC, 0xCC, 0x00, 0x00
|
||||
|
||||
/*
|
||||
// Set properties: RF_PKT_CRC_CONFIG_7
|
||||
// Number of properties: 7
|
||||
// Group ID: 0x12
|
||||
// Start ID: 0x00
|
||||
// Default values: 0x00, 0x01, 0x08, 0xFF, 0xFF, 0x00, 0x00,
|
||||
// Descriptions:
|
||||
// PKT_CRC_CONFIG - Select a CRC polynomial and seed.
|
||||
// PKT_WHT_POLY_15_8 - 16-bit polynomial value for the PN Generator (e.g., for Data Whitening)
|
||||
// PKT_WHT_POLY_7_0 - 16-bit polynomial value for the PN Generator (e.g., for Data Whitening)
|
||||
// PKT_WHT_SEED_15_8 - 16-bit seed value for the PN Generator (e.g., for Data Whitening)
|
||||
// PKT_WHT_SEED_7_0 - 16-bit seed value for the PN Generator (e.g., for Data Whitening)
|
||||
// PKT_WHT_BIT_NUM - Selects which bit of the LFSR (used to generate the PN / data whitening sequence) is used as the output bit for data scrambling.
|
||||
// PKT_CONFIG1 - General configuration bits for transmission or reception of a packet.
|
||||
*/
|
||||
#define RF_PKT_CRC_CONFIG_7 0x11, 0x12, 0x07, 0x00, 0x80, 0x01, 0x08, 0xFF, 0xFF, 0x00, 0x02
|
||||
|
||||
/*
|
||||
// Set properties: RF_PKT_LEN_12
|
||||
// Number of properties: 12
|
||||
// Group ID: 0x12
|
||||
// Start ID: 0x08
|
||||
// Default values: 0x00, 0x00, 0x00, 0x30, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
// Descriptions:
|
||||
// PKT_LEN - Configuration bits for reception of a variable length packet.
|
||||
// PKT_LEN_FIELD_SOURCE - Field number containing the received packet length byte(s).
|
||||
// PKT_LEN_ADJUST - Provides for adjustment/offset of the received packet length value (in order to accommodate a variety of methods of defining total packet length).
|
||||
// PKT_TX_THRESHOLD - TX FIFO almost empty threshold.
|
||||
// PKT_RX_THRESHOLD - RX FIFO Almost Full threshold.
|
||||
// PKT_FIELD_1_LENGTH_12_8 - Unsigned 13-bit Field 1 length value.
|
||||
// PKT_FIELD_1_LENGTH_7_0 - Unsigned 13-bit Field 1 length value.
|
||||
// PKT_FIELD_1_CONFIG - General data processing and packet configuration bits for Field 1.
|
||||
// PKT_FIELD_1_CRC_CONFIG - Configuration of CRC control bits across Field 1.
|
||||
// PKT_FIELD_2_LENGTH_12_8 - Unsigned 13-bit Field 2 length value.
|
||||
// PKT_FIELD_2_LENGTH_7_0 - Unsigned 13-bit Field 2 length value.
|
||||
// PKT_FIELD_2_CONFIG - General data processing and packet configuration bits for Field 2.
|
||||
*/
|
||||
#define RF_PKT_LEN_12 0x11, 0x12, 0x0C, 0x08, 0x00, 0x00, 0x00, 0x40, 0x40, 0x00, 0x40, 0x04, 0x00, 0x00, 0x00, 0x00
|
||||
|
||||
/*
|
||||
// Set properties: RF_PKT_FIELD_2_CRC_CONFIG_12
|
||||
// Number of properties: 12
|
||||
// Group ID: 0x12
|
||||
// Start ID: 0x14
|
||||
// Default values: 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
// Descriptions:
|
||||
// PKT_FIELD_2_CRC_CONFIG - Configuration of CRC control bits across Field 2.
|
||||
// PKT_FIELD_3_LENGTH_12_8 - Unsigned 13-bit Field 3 length value.
|
||||
// PKT_FIELD_3_LENGTH_7_0 - Unsigned 13-bit Field 3 length value.
|
||||
// PKT_FIELD_3_CONFIG - General data processing and packet configuration bits for Field 3.
|
||||
// PKT_FIELD_3_CRC_CONFIG - Configuration of CRC control bits across Field 3.
|
||||
// PKT_FIELD_4_LENGTH_12_8 - Unsigned 13-bit Field 4 length value.
|
||||
// PKT_FIELD_4_LENGTH_7_0 - Unsigned 13-bit Field 4 length value.
|
||||
// PKT_FIELD_4_CONFIG - General data processing and packet configuration bits for Field 4.
|
||||
// PKT_FIELD_4_CRC_CONFIG - Configuration of CRC control bits across Field 4.
|
||||
// PKT_FIELD_5_LENGTH_12_8 - Unsigned 13-bit Field 5 length value.
|
||||
// PKT_FIELD_5_LENGTH_7_0 - Unsigned 13-bit Field 5 length value.
|
||||
// PKT_FIELD_5_CONFIG - General data processing and packet configuration bits for Field 5.
|
||||
*/
|
||||
#define RF_PKT_FIELD_2_CRC_CONFIG_12 0x11, 0x12, 0x0C, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
|
||||
/*
|
||||
// Set properties: RF_PKT_FIELD_5_CRC_CONFIG_12
|
||||
// Number of properties: 12
|
||||
// Group ID: 0x12
|
||||
// Start ID: 0x20
|
||||
// Default values: 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
// Descriptions:
|
||||
// PKT_FIELD_5_CRC_CONFIG - Configuration of CRC control bits across Field 5.
|
||||
// PKT_RX_FIELD_1_LENGTH_12_8 - Unsigned 13-bit RX Field 1 length value.
|
||||
// PKT_RX_FIELD_1_LENGTH_7_0 - Unsigned 13-bit RX Field 1 length value.
|
||||
// PKT_RX_FIELD_1_CONFIG - General data processing and packet configuration bits for RX Field 1.
|
||||
// PKT_RX_FIELD_1_CRC_CONFIG - Configuration of CRC control bits across RX Field 1.
|
||||
// PKT_RX_FIELD_2_LENGTH_12_8 - Unsigned 13-bit RX Field 2 length value.
|
||||
// PKT_RX_FIELD_2_LENGTH_7_0 - Unsigned 13-bit RX Field 2 length value.
|
||||
// PKT_RX_FIELD_2_CONFIG - General data processing and packet configuration bits for RX Field 2.
|
||||
// PKT_RX_FIELD_2_CRC_CONFIG - Configuration of CRC control bits across RX Field 2.
|
||||
// PKT_RX_FIELD_3_LENGTH_12_8 - Unsigned 13-bit RX Field 3 length value.
|
||||
// PKT_RX_FIELD_3_LENGTH_7_0 - Unsigned 13-bit RX Field 3 length value.
|
||||
// PKT_RX_FIELD_3_CONFIG - General data processing and packet configuration bits for RX Field 3.
|
||||
*/
|
||||
#define RF_PKT_FIELD_5_CRC_CONFIG_12 0x11, 0x12, 0x0C, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
|
||||
/*
|
||||
// Set properties: RF_PKT_RX_FIELD_3_CRC_CONFIG_9
|
||||
// Number of properties: 9
|
||||
// Group ID: 0x12
|
||||
// Start ID: 0x2C
|
||||
// Default values: 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
// Descriptions:
|
||||
// PKT_RX_FIELD_3_CRC_CONFIG - Configuration of CRC control bits across RX Field 3.
|
||||
// PKT_RX_FIELD_4_LENGTH_12_8 - Unsigned 13-bit RX Field 4 length value.
|
||||
// PKT_RX_FIELD_4_LENGTH_7_0 - Unsigned 13-bit RX Field 4 length value.
|
||||
// PKT_RX_FIELD_4_CONFIG - General data processing and packet configuration bits for RX Field 4.
|
||||
// PKT_RX_FIELD_4_CRC_CONFIG - Configuration of CRC control bits across RX Field 4.
|
||||
// PKT_RX_FIELD_5_LENGTH_12_8 - Unsigned 13-bit RX Field 5 length value.
|
||||
// PKT_RX_FIELD_5_LENGTH_7_0 - Unsigned 13-bit RX Field 5 length value.
|
||||
// PKT_RX_FIELD_5_CONFIG - General data processing and packet configuration bits for RX Field 5.
|
||||
// PKT_RX_FIELD_5_CRC_CONFIG - Configuration of CRC control bits across RX Field 5.
|
||||
*/
|
||||
#define RF_PKT_RX_FIELD_3_CRC_CONFIG_9 0x11, 0x12, 0x09, 0x2C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_MOD_TYPE_12
|
||||
// Number of properties: 12
|
||||
// Group ID: 0x20
|
||||
// Start ID: 0x00
|
||||
// Default values: 0x02, 0x80, 0x07, 0x0F, 0x42, 0x40, 0x01, 0xC9, 0xC3, 0x80, 0x00, 0x06,
|
||||
// Descriptions:
|
||||
// MODEM_MOD_TYPE - Selects the type of modulation. In TX mode, additionally selects the source of the modulation.
|
||||
// MODEM_MAP_CONTROL - Controls polarity and mapping of transmit and receive bits.
|
||||
// MODEM_DSM_CTRL - Miscellaneous control bits for the Delta-Sigma Modulator (DSM) in the PLL Synthesizer.
|
||||
// MODEM_DATA_RATE_2 - Unsigned 24-bit value used to determine the TX data rate
|
||||
// MODEM_DATA_RATE_1 - Unsigned 24-bit value used to determine the TX data rate
|
||||
// MODEM_DATA_RATE_0 - Unsigned 24-bit value used to determine the TX data rate
|
||||
// MODEM_TX_NCO_MODE_3 - TX Gaussian filter oversampling ratio and Byte 3 of unsigned 26-bit TX Numerically Controlled Oscillator (NCO) modulus.
|
||||
// MODEM_TX_NCO_MODE_2 - TX Gaussian filter oversampling ratio and Byte 3 of unsigned 26-bit TX Numerically Controlled Oscillator (NCO) modulus.
|
||||
// MODEM_TX_NCO_MODE_1 - TX Gaussian filter oversampling ratio and Byte 3 of unsigned 26-bit TX Numerically Controlled Oscillator (NCO) modulus.
|
||||
// MODEM_TX_NCO_MODE_0 - TX Gaussian filter oversampling ratio and Byte 3 of unsigned 26-bit TX Numerically Controlled Oscillator (NCO) modulus.
|
||||
// MODEM_FREQ_DEV_2 - 17-bit unsigned TX frequency deviation word.
|
||||
// MODEM_FREQ_DEV_1 - 17-bit unsigned TX frequency deviation word.
|
||||
*/
|
||||
#define RF_MODEM_MOD_TYPE_12 0x11, 0x20, 0x0C, 0x00, 0x03, 0x00, 0x07, 0x05, 0xDC, 0x00, 0x05, 0xC9, 0xC3, 0x80, 0x00, 0x01
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_FREQ_DEV_0_1
|
||||
// Number of properties: 1
|
||||
// Group ID: 0x20
|
||||
// Start ID: 0x0C
|
||||
// Default values: 0xD3,
|
||||
// Descriptions:
|
||||
// MODEM_FREQ_DEV_0 - 17-bit unsigned TX frequency deviation word.
|
||||
*/
|
||||
#define RF_MODEM_FREQ_DEV_0_1 0x11, 0x20, 0x01, 0x0C, 0xF7
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_TX_RAMP_DELAY_8
|
||||
// Number of properties: 8
|
||||
// Group ID: 0x20
|
||||
// Start ID: 0x18
|
||||
// Default values: 0x01, 0x00, 0x08, 0x03, 0xC0, 0x00, 0x10, 0x20,
|
||||
// Descriptions:
|
||||
// MODEM_TX_RAMP_DELAY - TX ramp-down delay setting.
|
||||
// MODEM_MDM_CTRL - MDM control.
|
||||
// MODEM_IF_CONTROL - Selects Fixed-IF, Scaled-IF, or Zero-IF mode of RX Modem operation.
|
||||
// MODEM_IF_FREQ_2 - the IF frequency setting (an 18-bit signed number).
|
||||
// MODEM_IF_FREQ_1 - the IF frequency setting (an 18-bit signed number).
|
||||
// MODEM_IF_FREQ_0 - the IF frequency setting (an 18-bit signed number).
|
||||
// MODEM_DECIMATION_CFG1 - Specifies three decimator ratios for the Cascaded Integrator Comb (CIC) filter.
|
||||
// MODEM_DECIMATION_CFG0 - Specifies miscellaneous parameters and decimator ratios for the Cascaded Integrator Comb (CIC) filter.
|
||||
*/
|
||||
#define RF_MODEM_TX_RAMP_DELAY_8 0x11, 0x20, 0x08, 0x18, 0x01, 0x80, 0x08, 0x02, 0x80, 0x00, 0x70, 0x20
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_BCR_OSR_1_9
|
||||
// Number of properties: 9
|
||||
// Group ID: 0x20
|
||||
// Start ID: 0x22
|
||||
// Default values: 0x00, 0x4B, 0x06, 0xD3, 0xA0, 0x06, 0xD3, 0x02, 0xC0,
|
||||
// Descriptions:
|
||||
// MODEM_BCR_OSR_1 - RX BCR/Slicer oversampling rate (12-bit unsigned number).
|
||||
// MODEM_BCR_OSR_0 - RX BCR/Slicer oversampling rate (12-bit unsigned number).
|
||||
// MODEM_BCR_NCO_OFFSET_2 - RX BCR NCO offset value (an unsigned 22-bit number).
|
||||
// MODEM_BCR_NCO_OFFSET_1 - RX BCR NCO offset value (an unsigned 22-bit number).
|
||||
// MODEM_BCR_NCO_OFFSET_0 - RX BCR NCO offset value (an unsigned 22-bit number).
|
||||
// MODEM_BCR_GAIN_1 - The unsigned 11-bit RX BCR loop gain value.
|
||||
// MODEM_BCR_GAIN_0 - The unsigned 11-bit RX BCR loop gain value.
|
||||
// MODEM_BCR_GEAR - RX BCR loop gear control.
|
||||
// MODEM_BCR_MISC1 - Miscellaneous control bits for the RX BCR loop.
|
||||
*/
|
||||
#define RF_MODEM_BCR_OSR_1_9 0x11, 0x20, 0x09, 0x22, 0x00, 0x62, 0x05, 0x3E, 0x2D, 0x02, 0x9D, 0x00, 0xC2
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_AFC_GEAR_7
|
||||
// Number of properties: 7
|
||||
// Group ID: 0x20
|
||||
// Start ID: 0x2C
|
||||
// Default values: 0x00, 0x23, 0x83, 0x69, 0x00, 0x40, 0xA0,
|
||||
// Descriptions:
|
||||
// MODEM_AFC_GEAR - RX AFC loop gear control.
|
||||
// MODEM_AFC_WAIT - RX AFC loop wait time control.
|
||||
// MODEM_AFC_GAIN_1 - Sets the gain of the PLL-based AFC acquisition loop, and provides miscellaneous control bits for AFC functionality.
|
||||
// MODEM_AFC_GAIN_0 - Sets the gain of the PLL-based AFC acquisition loop, and provides miscellaneous control bits for AFC functionality.
|
||||
// MODEM_AFC_LIMITER_1 - Set the AFC limiter value.
|
||||
// MODEM_AFC_LIMITER_0 - Set the AFC limiter value.
|
||||
// MODEM_AFC_MISC - Specifies miscellaneous AFC control bits.
|
||||
*/
|
||||
#define RF_MODEM_AFC_GEAR_7 0x11, 0x20, 0x07, 0x2C, 0x54, 0x36, 0x81, 0x01, 0x02, 0x13, 0x80
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_AGC_CONTROL_1
|
||||
// Number of properties: 1
|
||||
// Group ID: 0x20
|
||||
// Start ID: 0x35
|
||||
// Default values: 0xE0,
|
||||
// Descriptions:
|
||||
// MODEM_AGC_CONTROL - Miscellaneous control bits for the Automatic Gain Control (AGC) function in the RX Chain.
|
||||
*/
|
||||
#define RF_MODEM_AGC_CONTROL_1 0x11, 0x20, 0x01, 0x35, 0xE2
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_AGC_WINDOW_SIZE_9
|
||||
// Number of properties: 9
|
||||
// Group ID: 0x20
|
||||
// Start ID: 0x38
|
||||
// Default values: 0x11, 0x10, 0x10, 0x0B, 0x1C, 0x40, 0x00, 0x00, 0x2B,
|
||||
// Descriptions:
|
||||
// MODEM_AGC_WINDOW_SIZE - Specifies the size of the measurement and settling windows for the AGC algorithm.
|
||||
// MODEM_AGC_RFPD_DECAY - Sets the decay time of the RF peak detectors.
|
||||
// MODEM_AGC_IFPD_DECAY - Sets the decay time of the IF peak detectors.
|
||||
// MODEM_FSK4_GAIN1 - Specifies the gain factor of the secondary branch in 4(G)FSK ISI-suppression.
|
||||
// MODEM_FSK4_GAIN0 - Specifies the gain factor of the primary branch in 4(G)FSK ISI-suppression.
|
||||
// MODEM_FSK4_TH1 - 16 bit 4(G)FSK slicer threshold.
|
||||
// MODEM_FSK4_TH0 - 16 bit 4(G)FSK slicer threshold.
|
||||
// MODEM_FSK4_MAP - 4(G)FSK symbol mapping code.
|
||||
// MODEM_OOK_PDTC - Configures the attack and decay times of the OOK Peak Detector.
|
||||
*/
|
||||
#define RF_MODEM_AGC_WINDOW_SIZE_9 0x11, 0x20, 0x09, 0x38, 0x11, 0x15, 0x15, 0x00, 0x1A, 0x20, 0x00, 0x00, 0x28
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_OOK_CNT1_9
|
||||
// Number of properties: 9
|
||||
// Group ID: 0x20
|
||||
// Start ID: 0x42
|
||||
// Default values: 0xA4, 0x03, 0x56, 0x02, 0x00, 0xA3, 0x02, 0x80, 0xFF,
|
||||
// Descriptions:
|
||||
// MODEM_OOK_CNT1 - OOK control.
|
||||
// MODEM_OOK_MISC - Selects the detector(s) used for demodulation of an OOK signal, or for demodulation of a (G)FSK signal when using the asynchronous demodulator.
|
||||
// MODEM_RAW_SEARCH - Defines and controls the search period length for the Moving Average and Min-Max detectors.
|
||||
// MODEM_RAW_CONTROL - Defines gain and enable controls for raw / nonstandard mode.
|
||||
// MODEM_RAW_EYE_1 - 11 bit eye-open detector threshold.
|
||||
// MODEM_RAW_EYE_0 - 11 bit eye-open detector threshold.
|
||||
// MODEM_ANT_DIV_MODE - Antenna diversity mode settings.
|
||||
// MODEM_ANT_DIV_CONTROL - Specifies controls for the Antenna Diversity algorithm.
|
||||
// MODEM_RSSI_THRESH - Configures the RSSI threshold.
|
||||
*/
|
||||
#define RF_MODEM_OOK_CNT1_9 0x11, 0x20, 0x09, 0x42, 0x84, 0x03, 0xD6, 0x8F, 0x00, 0x62, 0x01, 0x80, 0xFF
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_RSSI_CONTROL_1
|
||||
// Number of properties: 1
|
||||
// Group ID: 0x20
|
||||
// Start ID: 0x4C
|
||||
// Default values: 0x01,
|
||||
// Descriptions:
|
||||
// MODEM_RSSI_CONTROL - Control of the averaging modes and latching time for reporting RSSI value(s).
|
||||
*/
|
||||
#define RF_MODEM_RSSI_CONTROL_1 0x11, 0x20, 0x01, 0x4C, 0x00
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_RSSI_COMP_1
|
||||
// Number of properties: 1
|
||||
// Group ID: 0x20
|
||||
// Start ID: 0x4E
|
||||
// Default values: 0x32,
|
||||
// Descriptions:
|
||||
// MODEM_RSSI_COMP - RSSI compensation value.
|
||||
*/
|
||||
#define RF_MODEM_RSSI_COMP_1 0x11, 0x20, 0x01, 0x4E, 0x40
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_CLKGEN_BAND_1
|
||||
// Number of properties: 1
|
||||
// Group ID: 0x20
|
||||
// Start ID: 0x51
|
||||
// Default values: 0x08,
|
||||
// Descriptions:
|
||||
// MODEM_CLKGEN_BAND - Select PLL Synthesizer output divider ratio as a function of frequency band.
|
||||
*/
|
||||
#define RF_MODEM_CLKGEN_BAND_1 0x11, 0x20, 0x01, 0x51, 0x0D
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12
|
||||
// Number of properties: 12
|
||||
// Group ID: 0x21
|
||||
// Start ID: 0x00
|
||||
// Default values: 0xFF, 0xBA, 0x0F, 0x51, 0xCF, 0xA9, 0xC9, 0xFC, 0x1B, 0x1E, 0x0F, 0x01,
|
||||
// Descriptions:
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE13_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE12_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE11_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE10_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE9_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE8_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE7_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE6_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE5_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE4_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE3_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE2_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
*/
|
||||
#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12 0x11, 0x21, 0x0C, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12
|
||||
// Number of properties: 12
|
||||
// Group ID: 0x21
|
||||
// Start ID: 0x0C
|
||||
// Default values: 0xFC, 0xFD, 0x15, 0xFF, 0x00, 0x0F, 0xFF, 0xC4, 0x30, 0x7F, 0xF5, 0xB5,
|
||||
// Descriptions:
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE1_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COE0_7_0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COEM0 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COEM1 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COEM2 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX1_CHFLT_COEM3 - Filter coefficients for the first set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE13_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE12_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE11_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE10_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE9_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE8_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
*/
|
||||
#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12 0x11, 0x21, 0x0C, 0x0C, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1
|
||||
|
||||
/*
|
||||
// Set properties: RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12
|
||||
// Number of properties: 12
|
||||
// Group ID: 0x21
|
||||
// Start ID: 0x18
|
||||
// Default values: 0xB8, 0xDE, 0x05, 0x17, 0x16, 0x0C, 0x03, 0x00, 0x15, 0xFF, 0x00, 0x00,
|
||||
// Descriptions:
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE7_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE6_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE5_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE4_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE3_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE2_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE1_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COE0_7_0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COEM0 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COEM1 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COEM2 - Filter coefficients for the second set of RX filter coefficients.
|
||||
// MODEM_CHFLT_RX2_CHFLT_COEM3 - Filter coefficients for the second set of RX filter coefficients.
|
||||
*/
|
||||
#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12 0x11, 0x21, 0x0C, 0x18, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00
|
||||
|
||||
/*
|
||||
// Set properties: RF_PA_MODE_4
|
||||
// Number of properties: 4
|
||||
// Group ID: 0x22
|
||||
// Start ID: 0x00
|
||||
// Default values: 0x08, 0x7F, 0x00, 0x5D,
|
||||
// Descriptions:
|
||||
// PA_MODE - Selects the PA operating mode, and selects resolution of PA power adjustment (i.e., step size).
|
||||
// PA_PWR_LVL - Configuration of PA output power level.
|
||||
// PA_BIAS_CLKDUTY - Configuration of the PA Bias and duty cycle of the TX clock source.
|
||||
// PA_TC - Configuration of PA ramping parameters.
|
||||
*/
|
||||
#define RF_PA_MODE_4 0x11, 0x22, 0x04, 0x00, 0x18, 0x2C, 0xC0, 0x3D
|
||||
|
||||
/*
|
||||
// Set properties: RF_SYNTH_PFDCP_CPFF_7
|
||||
// Number of properties: 7
|
||||
// Group ID: 0x23
|
||||
// Start ID: 0x00
|
||||
// Default values: 0x2C, 0x0E, 0x0B, 0x04, 0x0C, 0x73, 0x03,
|
||||
// Descriptions:
|
||||
// SYNTH_PFDCP_CPFF - Feed forward charge pump current selection.
|
||||
// SYNTH_PFDCP_CPINT - Integration charge pump current selection.
|
||||
// SYNTH_VCO_KV - Gain scaling factors (Kv) for the VCO tuning varactors on both the integrated-path and feed forward path.
|
||||
// SYNTH_LPFILT3 - Value of resistor R2 in feed-forward path of loop filter.
|
||||
// SYNTH_LPFILT2 - Value of capacitor C2 in feed-forward path of loop filter.
|
||||
// SYNTH_LPFILT1 - Value of capacitors C1 and C3 in feed-forward path of loop filter.
|
||||
// SYNTH_LPFILT0 - Bias current of the active amplifier in the feed-forward loop filter.
|
||||
*/
|
||||
#define RF_SYNTH_PFDCP_CPFF_7 0x11, 0x23, 0x07, 0x00, 0x2C, 0x0E, 0x0B, 0x04, 0x0C, 0x73, 0x03
|
||||
|
||||
/*
|
||||
// Set properties: RF_MATCH_VALUE_1_12
|
||||
// Number of properties: 12
|
||||
// Group ID: 0x30
|
||||
// Start ID: 0x00
|
||||
// Default values: 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
// Descriptions:
|
||||
// MATCH_VALUE_1 - Match value to be compared with the result of logically AND-ing (bit-wise) the Mask 1 value with the received Match 1 byte.
|
||||
// MATCH_MASK_1 - Mask value to be logically AND-ed (bit-wise) with the Match 1 byte.
|
||||
// MATCH_CTRL_1 - Enable for Packet Match functionality, and configuration of Match Byte 1.
|
||||
// MATCH_VALUE_2 - Match value to be compared with the result of logically AND-ing (bit-wise) the Mask 2 value with the received Match 2 byte.
|
||||
// MATCH_MASK_2 - Mask value to be logically AND-ed (bit-wise) with the Match 2 byte.
|
||||
// MATCH_CTRL_2 - Configuration of Match Byte 2.
|
||||
// MATCH_VALUE_3 - Match value to be compared with the result of logically AND-ing (bit-wise) the Mask 3 value with the received Match 3 byte.
|
||||
// MATCH_MASK_3 - Mask value to be logically AND-ed (bit-wise) with the Match 3 byte.
|
||||
// MATCH_CTRL_3 - Configuration of Match Byte 3.
|
||||
// MATCH_VALUE_4 - Match value to be compared with the result of logically AND-ing (bit-wise) the Mask 4 value with the received Match 4 byte.
|
||||
// MATCH_MASK_4 - Mask value to be logically AND-ed (bit-wise) with the Match 4 byte.
|
||||
// MATCH_CTRL_4 - Configuration of Match Byte 4.
|
||||
*/
|
||||
#define RF_MATCH_VALUE_1_12 0x11, 0x30, 0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
|
||||
/*
|
||||
// Set properties: RF_FREQ_CONTROL_INTE_8
|
||||
// Number of properties: 8
|
||||
// Group ID: 0x40
|
||||
// Start ID: 0x00
|
||||
// Default values: 0x3C, 0x08, 0x00, 0x00, 0x00, 0x00, 0x20, 0xFF,
|
||||
// Descriptions:
|
||||
// FREQ_CONTROL_INTE - Frac-N PLL Synthesizer integer divide number.
|
||||
// FREQ_CONTROL_FRAC_2 - Frac-N PLL fraction number.
|
||||
// FREQ_CONTROL_FRAC_1 - Frac-N PLL fraction number.
|
||||
// FREQ_CONTROL_FRAC_0 - Frac-N PLL fraction number.
|
||||
// FREQ_CONTROL_CHANNEL_STEP_SIZE_1 - EZ Frequency Programming channel step size.
|
||||
// FREQ_CONTROL_CHANNEL_STEP_SIZE_0 - EZ Frequency Programming channel step size.
|
||||
// FREQ_CONTROL_W_SIZE - Set window gating period (in number of crystal reference clock cycles) for counting VCO frequency during calibration.
|
||||
// FREQ_CONTROL_VCOCNT_RX_ADJ - Adjust target count for VCO calibration in RX mode.
|
||||
*/
|
||||
#define RF_FREQ_CONTROL_INTE_8 0x11, 0x40, 0x08, 0x00, 0x3F, 0x0C, 0xCC, 0xCC, 0x14, 0x7B, 0x20, 0xFA
|
||||
|
||||
|
||||
// AUTOMATICALLY GENERATED CODE!
|
||||
// DO NOT EDIT/MODIFY BELOW THIS LINE!
|
||||
// --------------------------------------------
|
||||
|
||||
#ifndef FIRMWARE_LOAD_COMPILE
|
||||
#define RADIO_CONFIGURATION_DATA_ARRAY { \
|
||||
0x07, RF_POWER_UP, \
|
||||
0x08, RF_GPIO_PIN_CFG, \
|
||||
0x06, RF_GLOBAL_XO_TUNE_2, \
|
||||
0x05, RF_GLOBAL_CONFIG_1, \
|
||||
0x05, RF_INT_CTL_ENABLE_1, \
|
||||
0x08, RF_FRR_CTL_A_MODE_4, \
|
||||
0x0D, RF_PREAMBLE_TX_LENGTH_9, \
|
||||
0x09, RF_SYNC_CONFIG_5, \
|
||||
0x0B, RF_PKT_CRC_CONFIG_7, \
|
||||
0x10, RF_PKT_LEN_12, \
|
||||
0x10, RF_PKT_FIELD_2_CRC_CONFIG_12, \
|
||||
0x10, RF_PKT_FIELD_5_CRC_CONFIG_12, \
|
||||
0x0D, RF_PKT_RX_FIELD_3_CRC_CONFIG_9, \
|
||||
0x10, RF_MODEM_MOD_TYPE_12, \
|
||||
0x05, RF_MODEM_FREQ_DEV_0_1, \
|
||||
0x0C, RF_MODEM_TX_RAMP_DELAY_8, \
|
||||
0x0D, RF_MODEM_BCR_OSR_1_9, \
|
||||
0x0B, RF_MODEM_AFC_GEAR_7, \
|
||||
0x05, RF_MODEM_AGC_CONTROL_1, \
|
||||
0x0D, RF_MODEM_AGC_WINDOW_SIZE_9, \
|
||||
0x0D, RF_MODEM_OOK_CNT1_9, \
|
||||
0x05, RF_MODEM_RSSI_CONTROL_1, \
|
||||
0x05, RF_MODEM_RSSI_COMP_1, \
|
||||
0x05, RF_MODEM_CLKGEN_BAND_1, \
|
||||
0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12, \
|
||||
0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12, \
|
||||
0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12, \
|
||||
0x08, RF_PA_MODE_4, \
|
||||
0x0B, RF_SYNTH_PFDCP_CPFF_7, \
|
||||
0x10, RF_MATCH_VALUE_1_12, \
|
||||
0x0C, RF_FREQ_CONTROL_INTE_8, \
|
||||
0x00 \
|
||||
}
|
||||
#else
|
||||
#define RADIO_CONFIGURATION_DATA_ARRAY { 0 }
|
||||
#endif
|
||||
|
||||
// DEFAULT VALUES FOR CONFIGURATION PARAMETERS
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_XO_FREQ_DEFAULT 30000000L
|
||||
#define RADIO_CONFIGURATION_DATA_CHANNEL_NUMBER_DEFAULT 0x00
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_PACKET_LENGTH_DEFAULT 0x10
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_STATE_AFTER_POWER_UP_DEFAULT 0x01
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_DELAY_CNT_AFTER_RESET_DEFAULT 0x1000
|
||||
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_PATCH_INCLUDED 0x00
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_PATCH_SIZE 0x00
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_PATCH { }
|
||||
|
||||
#ifndef RADIO_CONFIGURATION_DATA_ARRAY
|
||||
#error "This property must be defined!"
|
||||
#endif
|
||||
|
||||
#ifndef RADIO_CONFIGURATION_DATA_RADIO_XO_FREQ
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_XO_FREQ RADIO_CONFIGURATION_DATA_RADIO_XO_FREQ_DEFAULT
|
||||
#endif
|
||||
|
||||
#ifndef RADIO_CONFIGURATION_DATA_CHANNEL_NUMBER
|
||||
#define RADIO_CONFIGURATION_DATA_CHANNEL_NUMBER RADIO_CONFIGURATION_DATA_CHANNEL_NUMBER_DEFAULT
|
||||
#endif
|
||||
|
||||
#ifndef RADIO_CONFIGURATION_DATA_RADIO_PACKET_LENGTH
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_PACKET_LENGTH RADIO_CONFIGURATION_DATA_RADIO_PACKET_LENGTH_DEFAULT
|
||||
#endif
|
||||
|
||||
#ifndef RADIO_CONFIGURATION_DATA_RADIO_STATE_AFTER_POWER_UP
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_STATE_AFTER_POWER_UP RADIO_CONFIGURATION_DATA_RADIO_STATE_AFTER_POWER_UP_DEFAULT
|
||||
#endif
|
||||
|
||||
#ifndef RADIO_CONFIGURATION_DATA_RADIO_DELAY_CNT_AFTER_RESET
|
||||
#define RADIO_CONFIGURATION_DATA_RADIO_DELAY_CNT_AFTER_RESET RADIO_CONFIGURATION_DATA_RADIO_DELAY_CNT_AFTER_RESET_DEFAULT
|
||||
#endif
|
||||
|
||||
#define RADIO_CONFIGURATION_DATA { \
|
||||
Radio_Configuration_Data_Array, \
|
||||
RADIO_CONFIGURATION_DATA_CHANNEL_NUMBER, \
|
||||
RADIO_CONFIGURATION_DATA_RADIO_PACKET_LENGTH, \
|
||||
RADIO_CONFIGURATION_DATA_RADIO_STATE_AFTER_POWER_UP, \
|
||||
RADIO_CONFIGURATION_DATA_RADIO_DELAY_CNT_AFTER_RESET \
|
||||
}
|
||||
|
||||
#endif /* RADIO_CONFIG_H_ */
|
@ -163,12 +163,13 @@ void RFIC::configure()
|
||||
case 0x4467:
|
||||
radio_configuration = get_si4467_config_array();
|
||||
break;
|
||||
case 0x4460:
|
||||
radio_configuration = get_si4460_config_array();
|
||||
break;
|
||||
default:
|
||||
radio_configuration = get_si4463_config_array();
|
||||
}
|
||||
|
||||
|
||||
//uint8_t radio_configuration[] = RADIO_CONFIGURATION_DATA_ARRAY;
|
||||
uint8_t *cfg = radio_configuration;
|
||||
while (*cfg)
|
||||
{ // configuration array stops with 0
|
||||
|
656
latest/Firmware/Src/bsp/bsp_10_5.cpp
Normal file
656
latest/Firmware/Src/bsp/bsp_10_5.cpp
Normal file
@ -0,0 +1,656 @@
|
||||
/*
|
||||
Copyright (c) 2016-2020 Peter Antypas
|
||||
|
||||
This file is part of the MAIANA™ transponder firmware.
|
||||
|
||||
The firmware 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 <https://www.gnu.org/licenses/>
|
||||
*/
|
||||
|
||||
|
||||
|
||||
#include "bsp.hpp"
|
||||
#include <stm32l4xx_hal.h>
|
||||
#include "printf_serial.h"
|
||||
#include <string.h>
|
||||
|
||||
|
||||
#if BOARD_REV==105
|
||||
|
||||
//I2C_HandleTypeDef hi2c1;
|
||||
SPI_HandleTypeDef hspi1;
|
||||
IWDG_HandleTypeDef hiwdg;
|
||||
UART_HandleTypeDef huart2;
|
||||
UART_HandleTypeDef huart1;
|
||||
TIM_HandleTypeDef htim2;
|
||||
|
||||
void SystemClock_Config();
|
||||
|
||||
char_input_cb gnssInputCallback = nullptr;
|
||||
char_input_cb terminalInputCallback = nullptr;
|
||||
irq_callback ppsCallback = nullptr;
|
||||
irq_callback sotdmaCallback = nullptr;
|
||||
irq_callback trxClockCallback = nullptr;
|
||||
irq_callback rxClockCallback = nullptr;
|
||||
|
||||
#define EEPROM_ADDRESS 0x50 << 1
|
||||
|
||||
typedef struct
|
||||
{
|
||||
GPIO_TypeDef *port;
|
||||
GPIO_InitTypeDef gpio;
|
||||
GPIO_PinState init;
|
||||
} GPIO;
|
||||
|
||||
static const GPIO __gpios[] = {
|
||||
{GNSS_EN_PORT, {GNSS_EN_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
|
||||
{TRX_IC_CLK_PORT, {TRX_IC_CLK_PIN, GPIO_MODE_IT_RISING, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
|
||||
{TX_DISABLE_PORT, {TX_DISABLE_PIN, GPIO_MODE_INPUT, GPIO_PULLUP, GPIO_SPEED_LOW, 0}, GPIO_PIN_SET},
|
||||
{CS2_PORT, {CS2_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_HIGH, 0}, GPIO_PIN_SET},
|
||||
{RX_EVT_PORT, {RX_EVT_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
|
||||
{GNSS_1PPS_PORT, {GNSS_1PPS_PIN, GPIO_MODE_IT_FALLING, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
|
||||
{GNSS_NMEA_RX_PORT, {GNSS_NMEA_RX_PIN, GPIO_MODE_AF_PP, GPIO_PULLUP, GPIO_SPEED_LOW, GPIO_AF7_USART2}, GPIO_PIN_RESET},
|
||||
{CS1_PORT, {CS1_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_HIGH, 0}, GPIO_PIN_SET},
|
||||
{SCK_PORT, {SCK_PIN, GPIO_MODE_AF_PP, GPIO_NOPULL, GPIO_SPEED_HIGH, GPIO_AF5_SPI1}, GPIO_PIN_SET},
|
||||
{MISO_PORT, {MISO_PIN, GPIO_MODE_AF_PP, GPIO_NOPULL, GPIO_SPEED_HIGH, GPIO_AF5_SPI1}, GPIO_PIN_SET},
|
||||
{MOSI_PORT, {MOSI_PIN, GPIO_MODE_AF_PP, GPIO_NOPULL, GPIO_SPEED_HIGH, GPIO_AF5_SPI1}, GPIO_PIN_SET},
|
||||
{SDN1_PORT, {SDN1_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_SET},
|
||||
{TRX_IC_DATA_PORT, {TRX_IC_DATA_PIN, GPIO_MODE_INPUT, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
|
||||
{TX_EVT_PORT, {TX_EVT_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
|
||||
{UART_TX_PORT, {UART_TX_PIN, GPIO_MODE_AF_PP, GPIO_PULLUP, GPIO_SPEED_LOW, GPIO_AF7_USART1}, GPIO_PIN_RESET},
|
||||
{UART_RX_PORT, {UART_RX_PIN, GPIO_MODE_AF_PP, GPIO_PULLUP, GPIO_SPEED_LOW, GPIO_AF7_USART1}, GPIO_PIN_RESET},
|
||||
{GNSS_STATE_PORT, {GNSS_STATE_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
|
||||
{SDN2_PORT, {SDN2_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_SET},
|
||||
{RX_IC_CLK_PORT, {RX_IC_CLK_PIN, GPIO_MODE_IT_RISING, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
|
||||
{RX_IC_DATA_PORT, {RX_IC_DATA_PIN, GPIO_MODE_INPUT, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
|
||||
{TX_CTRL_PORT, {TX_CTRL_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
|
||||
{RX_EN_PORT, {RX_EN_PIN, GPIO_MODE_AF_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_SET},
|
||||
};
|
||||
|
||||
extern "C"
|
||||
{
|
||||
void Error_Handler(uint8_t i)
|
||||
{
|
||||
asm("BKPT 0");
|
||||
printf_serial_now("[ERROR %d]\r\n", i);
|
||||
//printf_serial_now("[ERROR] ***** System error handler resetting *****\r\n");
|
||||
//NVIC_SystemReset();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void gpio_pin_init();
|
||||
|
||||
void bsp_hw_init()
|
||||
{
|
||||
HAL_Init();
|
||||
SystemClock_Config();
|
||||
|
||||
__HAL_RCC_GPIOA_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOB_CLK_ENABLE();
|
||||
__HAL_RCC_GPIOC_CLK_ENABLE();
|
||||
|
||||
__HAL_RCC_USART2_CLK_ENABLE();
|
||||
__HAL_RCC_USART1_CLK_ENABLE();
|
||||
__HAL_RCC_SPI1_CLK_ENABLE();
|
||||
__HAL_RCC_TIM2_CLK_ENABLE();
|
||||
__HAL_RCC_I2C1_CLK_ENABLE();
|
||||
|
||||
gpio_pin_init();
|
||||
|
||||
|
||||
|
||||
// USART1 (main UART)
|
||||
huart1.Instance = USART1;
|
||||
huart1.Init.BaudRate = 38400;
|
||||
huart1.Init.WordLength = UART_WORDLENGTH_8B;
|
||||
huart1.Init.StopBits = UART_STOPBITS_1;
|
||||
huart1.Init.Parity = UART_PARITY_NONE;
|
||||
huart1.Init.Mode = UART_MODE_TX_RX;
|
||||
huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE;
|
||||
huart1.Init.OverSampling = UART_OVERSAMPLING_16;
|
||||
huart1.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
|
||||
huart1.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
|
||||
HAL_UART_Init(&huart1);
|
||||
|
||||
HAL_NVIC_SetPriority(USART1_IRQn, 1, 0);
|
||||
HAL_NVIC_EnableIRQ(USART1_IRQn);
|
||||
__HAL_UART_ENABLE_IT(&huart1, UART_IT_RXNE);
|
||||
|
||||
|
||||
// SPI
|
||||
|
||||
hspi1.Instance = SPI1;
|
||||
hspi1.Init.Mode = SPI_MODE_MASTER;
|
||||
hspi1.Init.Direction = SPI_DIRECTION_2LINES;
|
||||
hspi1.Init.DataSize = SPI_DATASIZE_8BIT;
|
||||
hspi1.Init.CLKPolarity = SPI_POLARITY_LOW;
|
||||
hspi1.Init.CLKPhase = SPI_PHASE_1EDGE;
|
||||
hspi1.Init.NSS = SPI_NSS_SOFT;
|
||||
hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8;
|
||||
hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB;
|
||||
hspi1.Init.TIMode = SPI_TIMODE_DISABLE;
|
||||
hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
|
||||
hspi1.Init.CRCPolynomial = 7;
|
||||
hspi1.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
|
||||
hspi1.Init.NSSPMode = SPI_NSS_PULSE_DISABLE;
|
||||
|
||||
if (HAL_SPI_Init(&hspi1) != HAL_OK)
|
||||
{
|
||||
Error_Handler(0);
|
||||
}
|
||||
|
||||
__HAL_SPI_ENABLE(&hspi1);
|
||||
|
||||
|
||||
// USART2 (GNSS, RX only)
|
||||
huart2.Instance = USART2;
|
||||
huart2.Init.BaudRate = 9600;
|
||||
huart2.Init.WordLength = UART_WORDLENGTH_8B;
|
||||
huart2.Init.StopBits = UART_STOPBITS_1;
|
||||
huart2.Init.Parity = UART_PARITY_NONE;
|
||||
huart2.Init.Mode = UART_MODE_TX_RX;
|
||||
huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
|
||||
huart2.Init.OverSampling = UART_OVERSAMPLING_16;
|
||||
huart2.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
|
||||
huart2.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
|
||||
HAL_UART_Init(&huart2);
|
||||
|
||||
HAL_NVIC_SetPriority(USART2_IRQn, 7, 0);
|
||||
HAL_NVIC_EnableIRQ(USART2_IRQn);
|
||||
__HAL_UART_ENABLE_IT(&huart2, UART_IT_RXNE);
|
||||
|
||||
// TIM2 for SOTDMA (37.5Hz)
|
||||
uint32_t period = (SystemCoreClock / 37.5) - 1;
|
||||
|
||||
__HAL_RCC_TIM2_CLK_ENABLE();
|
||||
htim2.Instance = TIM2;
|
||||
htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||
htim2.Init.Prescaler = 0;
|
||||
htim2.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||
htim2.Init.Period = period;
|
||||
htim2.Init.RepetitionCounter = 0;
|
||||
|
||||
HAL_TIM_Base_Init(&htim2);
|
||||
|
||||
#if 0
|
||||
// I2C
|
||||
hi2c1.Instance = I2C1;
|
||||
hi2c1.Init.Timing = 0x00702991;
|
||||
hi2c1.Init.OwnAddress1 = 0;
|
||||
hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
|
||||
hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
|
||||
hi2c1.Init.OwnAddress2 = 0;
|
||||
hi2c1.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
|
||||
hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
|
||||
hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
|
||||
if (HAL_I2C_Init(&hi2c1) != HAL_OK)
|
||||
{
|
||||
Error_Handler(0);
|
||||
}
|
||||
/** Configure Analogue filter
|
||||
*/
|
||||
if (HAL_I2CEx_ConfigAnalogFilter(&hi2c1, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
|
||||
{
|
||||
Error_Handler(0);
|
||||
}
|
||||
/** Configure Digital filter
|
||||
*/
|
||||
if (HAL_I2CEx_ConfigDigitalFilter(&hi2c1, 0) != HAL_OK)
|
||||
{
|
||||
Error_Handler(0);
|
||||
}
|
||||
#endif
|
||||
|
||||
// 1PPS signal
|
||||
HAL_NVIC_SetPriority(EXTI2_IRQn, 6, 0);
|
||||
HAL_NVIC_EnableIRQ(EXTI2_IRQn);
|
||||
|
||||
// SOTDMA
|
||||
HAL_NVIC_SetPriority(TIM2_IRQn, 1, 0);
|
||||
HAL_NVIC_EnableIRQ(TIM2_IRQn);
|
||||
|
||||
// RF IC clock interrupts
|
||||
HAL_NVIC_SetPriority(EXTI15_10_IRQn, 1, 0);
|
||||
HAL_NVIC_EnableIRQ(EXTI15_10_IRQn);
|
||||
|
||||
HAL_NVIC_SetPriority(EXTI3_IRQn, 1, 0);
|
||||
HAL_NVIC_EnableIRQ(EXTI3_IRQn);
|
||||
|
||||
// This is our HAL tick timer now
|
||||
HAL_NVIC_SetPriority(TIM6_DAC_IRQn, 0, 0);
|
||||
}
|
||||
|
||||
|
||||
|
||||
void SystemClock_Config()
|
||||
{
|
||||
RCC_OscInitTypeDef RCC_OscInitStruct;
|
||||
RCC_ClkInitTypeDef RCC_ClkInitStruct;
|
||||
RCC_PeriphCLKInitTypeDef PeriphClkInit;
|
||||
|
||||
/**Initializes the CPU, AHB and APB bus clocks
|
||||
*/
|
||||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
|
||||
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
|
||||
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
|
||||
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
|
||||
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
|
||||
RCC_OscInitStruct.PLL.PLLM = 1;
|
||||
RCC_OscInitStruct.PLL.PLLN = 10; // 80 MHz
|
||||
//RCC_OscInitStruct.PLL.PLLN = 8; // 64 MHz
|
||||
//RCC_OscInitStruct.PLL.PLLN = 6; // 48 MHz
|
||||
#ifdef STM32L432xx
|
||||
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV7;
|
||||
#endif
|
||||
RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2;
|
||||
RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2;
|
||||
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
|
||||
{
|
||||
Error_Handler(0);
|
||||
}
|
||||
|
||||
/**Initializes the CPU, AHB and APB bus clocks
|
||||
*/
|
||||
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|
||||
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
|
||||
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
|
||||
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
|
||||
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
|
||||
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
|
||||
|
||||
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4) != HAL_OK)
|
||||
{
|
||||
Error_Handler(0);
|
||||
}
|
||||
|
||||
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1;
|
||||
PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_HSI;
|
||||
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
|
||||
{
|
||||
Error_Handler(0);
|
||||
}
|
||||
|
||||
/**Configure the main internal regulator output voltage
|
||||
*/
|
||||
if (HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1) != HAL_OK)
|
||||
{
|
||||
Error_Handler(0);
|
||||
}
|
||||
|
||||
/**Configure the Systick interrupt time
|
||||
*/
|
||||
HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000);
|
||||
|
||||
/**Configure the Systick
|
||||
*/
|
||||
HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);
|
||||
|
||||
/* SysTick_IRQn interrupt configuration */
|
||||
HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
|
||||
}
|
||||
|
||||
void gpio_pin_init()
|
||||
{
|
||||
for ( unsigned i = 0; i < sizeof __gpios / sizeof(GPIO); ++i )
|
||||
{
|
||||
const GPIO* io = &__gpios[i];
|
||||
HAL_GPIO_Init(io->port, (GPIO_InitTypeDef*)&io->gpio);
|
||||
if ( io->gpio.Mode == GPIO_MODE_OUTPUT_PP || io->gpio.Mode == GPIO_MODE_OUTPUT_OD )
|
||||
{
|
||||
HAL_GPIO_WritePin(io->port, io->gpio.Pin, io->init);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void HAL_MspInit(void)
|
||||
{
|
||||
/* USER CODE BEGIN MspInit 0 */
|
||||
|
||||
/* USER CODE END MspInit 0 */
|
||||
|
||||
__HAL_RCC_SYSCFG_CLK_ENABLE();
|
||||
__HAL_RCC_PWR_CLK_ENABLE();
|
||||
|
||||
HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4);
|
||||
|
||||
/**
|
||||
* Some of these interrupts will be managed and configured in FreeRTOS
|
||||
*/
|
||||
|
||||
/* System interrupt init*/
|
||||
/* MemoryManagement_IRQn interrupt configuration */
|
||||
HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0);
|
||||
/* BusFault_IRQn interrupt configuration */
|
||||
HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0);
|
||||
/* UsageFault_IRQn interrupt configuration */
|
||||
HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0);
|
||||
/* SVCall_IRQn interrupt configuration */
|
||||
HAL_NVIC_SetPriority(SVCall_IRQn, 10, 0);
|
||||
/* DebugMonitor_IRQn interrupt configuration */
|
||||
HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0);
|
||||
/* PendSV_IRQn interrupt configuration */
|
||||
HAL_NVIC_SetPriority(PendSV_IRQn, 10, 0);
|
||||
/* SysTick_IRQn interrupt configuration */
|
||||
|
||||
#ifndef RTOS
|
||||
HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
|
||||
#endif
|
||||
|
||||
/* USER CODE BEGIN MspInit 1 */
|
||||
|
||||
/* USER CODE END MspInit 1 */
|
||||
}
|
||||
|
||||
void bsp_set_rx_mode()
|
||||
{
|
||||
HAL_GPIO_WritePin(TX_CTRL_PORT, TX_CTRL_PIN, GPIO_PIN_RESET); // Kill the RF MOSFET bias voltage
|
||||
HAL_GPIO_WritePin(RX_EN_PORT, RX_EN_PIN, GPIO_PIN_SET); // Power up LNA, set switch to RX
|
||||
GPIO_InitTypeDef gpio;
|
||||
gpio.Pin = TRX_IC_DATA_PIN;
|
||||
gpio.Mode = GPIO_MODE_INPUT;
|
||||
gpio.Speed = GPIO_SPEED_FREQ_LOW;
|
||||
gpio.Pull = GPIO_NOPULL;
|
||||
HAL_GPIO_Init(TRX_IC_DATA_PORT, &gpio);
|
||||
}
|
||||
|
||||
void bsp_set_tx_mode()
|
||||
{
|
||||
HAL_GPIO_WritePin(RX_EN_PORT, RX_EN_PIN, GPIO_PIN_RESET); // Power down LNA, set switch to TX
|
||||
|
||||
GPIO_InitTypeDef gpio;
|
||||
gpio.Pin = TRX_IC_DATA_PIN;
|
||||
gpio.Mode = GPIO_MODE_OUTPUT_PP;
|
||||
gpio.Speed = GPIO_SPEED_FREQ_LOW;
|
||||
gpio.Pull = GPIO_NOPULL;
|
||||
HAL_GPIO_Init(TRX_IC_DATA_PORT, &gpio);
|
||||
|
||||
HAL_GPIO_WritePin(TX_CTRL_PORT, TX_CTRL_PIN, GPIO_PIN_SET); // RF MOSFET bias voltage
|
||||
}
|
||||
|
||||
void bsp_gnss_on()
|
||||
{
|
||||
HAL_GPIO_WritePin(GNSS_EN_PORT, GNSS_EN_PIN, GPIO_PIN_SET);
|
||||
}
|
||||
|
||||
void bsp_gnss_off()
|
||||
{
|
||||
HAL_GPIO_WritePin(GNSS_EN_PORT, GNSS_EN_PIN, GPIO_PIN_RESET);
|
||||
}
|
||||
|
||||
|
||||
void USART_putc(USART_TypeDef* USARTx, char c)
|
||||
{
|
||||
while ( !(USARTx->ISR & USART_ISR_TXE) )
|
||||
;
|
||||
|
||||
USARTx->TDR = c;
|
||||
}
|
||||
|
||||
void bsp_write_char(char c)
|
||||
{
|
||||
USART_putc(USART1, c);
|
||||
}
|
||||
|
||||
void bsp_write_string(const char *s)
|
||||
{
|
||||
for ( int i = 0; s[i] != 0; ++i )
|
||||
USART_putc(USART1, s[i]);
|
||||
}
|
||||
|
||||
void bsp_start_wdt()
|
||||
{
|
||||
IWDG_InitTypeDef iwdg;
|
||||
iwdg.Prescaler = IWDG_PRESCALER_64;
|
||||
iwdg.Reload = 0x0fff;
|
||||
iwdg.Window = 0x0fff;
|
||||
|
||||
hiwdg.Instance = IWDG;
|
||||
hiwdg.Init = iwdg;
|
||||
|
||||
HAL_IWDG_Init(&hiwdg);
|
||||
}
|
||||
|
||||
void bsp_refresh_wdt()
|
||||
{
|
||||
HAL_IWDG_Refresh(&hiwdg);
|
||||
}
|
||||
|
||||
void bsp_set_gnss_input_callback(char_input_cb cb)
|
||||
{
|
||||
gnssInputCallback = cb;
|
||||
}
|
||||
|
||||
void bsp_set_terminal_input_callback(char_input_cb cb)
|
||||
{
|
||||
terminalInputCallback = cb;
|
||||
}
|
||||
|
||||
void bsp_start_sotdma_timer()
|
||||
{
|
||||
HAL_TIM_Base_Start_IT(&htim2);
|
||||
}
|
||||
|
||||
void bsp_stop_sotdma_timer()
|
||||
{
|
||||
HAL_TIM_Base_Stop_IT(&htim2);
|
||||
}
|
||||
|
||||
void bsp_set_gnss_1pps_callback(irq_callback cb)
|
||||
{
|
||||
ppsCallback = cb;
|
||||
}
|
||||
|
||||
void bsp_set_trx_clk_callback(irq_callback cb)
|
||||
{
|
||||
trxClockCallback = cb;
|
||||
}
|
||||
|
||||
void bsp_set_rx_clk_callback(irq_callback cb)
|
||||
{
|
||||
rxClockCallback = cb;
|
||||
}
|
||||
|
||||
void bsp_set_gnss_sotdma_timer_callback(irq_callback cb)
|
||||
{
|
||||
sotdmaCallback = cb;
|
||||
}
|
||||
|
||||
uint32_t bsp_get_sotdma_timer_value()
|
||||
{
|
||||
return TIM2->CNT;
|
||||
}
|
||||
|
||||
void bsp_set_sotdma_timer_value(uint32_t v)
|
||||
{
|
||||
TIM2->CNT = v;
|
||||
}
|
||||
|
||||
uint32_t bsp_get_system_clock()
|
||||
{
|
||||
return SystemCoreClock;
|
||||
}
|
||||
|
||||
uint8_t bsp_tx_spi_byte(uint8_t data)
|
||||
{
|
||||
uint8_t result = 0;
|
||||
HAL_SPI_TransmitReceive(&hspi1, &data, &result, 1, 2);
|
||||
return result;
|
||||
}
|
||||
|
||||
bool bsp_erase_station_data()
|
||||
{
|
||||
#if 0
|
||||
uint8_t b = 0xff;
|
||||
HAL_Delay(1);
|
||||
|
||||
for ( unsigned i = 0; i < sizeof(StationData); ++i )
|
||||
{
|
||||
HAL_I2C_Mem_Write(&hi2c1, EEPROM_ADDRESS, i, 1, &b, 1, 100);
|
||||
HAL_Delay(6);
|
||||
}
|
||||
#endif
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool bsp_save_station_data(const StationData &data)
|
||||
{
|
||||
#if 0
|
||||
HAL_Delay(1);
|
||||
|
||||
uint8_t *b = (uint8_t*)&data;
|
||||
for ( unsigned i = 0; i < sizeof(StationData); ++i, ++b )
|
||||
{
|
||||
HAL_I2C_Mem_Write(&hi2c1, EEPROM_ADDRESS, i, 1, b, 1, 100);
|
||||
HAL_Delay(6);
|
||||
}
|
||||
#endif
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
void bsp_reboot()
|
||||
{
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
bool bsp_read_station_data(StationData &data)
|
||||
{
|
||||
#if 0
|
||||
uint8_t *b = (uint8_t*)&data;
|
||||
for ( unsigned i = 0; i < sizeof(StationData); ++i, ++b )
|
||||
{
|
||||
HAL_I2C_Mem_Read(&hi2c1, EEPROM_ADDRESS, i, 1, b, 1, 100);
|
||||
}
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
bool bsp_is_tx_disabled()
|
||||
{
|
||||
return HAL_GPIO_ReadPin(TX_DISABLE_PORT, TX_DISABLE_PIN) == GPIO_PIN_RESET;
|
||||
}
|
||||
|
||||
void bsp_enter_dfu()
|
||||
{
|
||||
// Cut off the GPS signals immediately to prevent its UART from transmitting and hijacking the bootloader upon reset
|
||||
bsp_gnss_off();
|
||||
|
||||
HAL_Delay(1000);
|
||||
|
||||
// This flag simply tells main() to jump to the ROM bootloader immediately upon reset, before initializing anything
|
||||
*(uint32_t*)BOOTMODE_ADDRESS = DFU_FLAG_MAGIC;
|
||||
|
||||
bsp_reboot();
|
||||
}
|
||||
|
||||
void bsp_signal_rx_event()
|
||||
{
|
||||
HAL_GPIO_WritePin(RX_EVT_PORT, RX_EVT_PIN, GPIO_PIN_SET);
|
||||
}
|
||||
|
||||
void bsp_signal_tx_event()
|
||||
{
|
||||
HAL_GPIO_WritePin(TX_EVT_PORT, TX_EVT_PIN, GPIO_PIN_SET);
|
||||
}
|
||||
|
||||
void bsp_signal_gps_status(bool tracking)
|
||||
{
|
||||
HAL_GPIO_WritePin(GNSS_STATE_PORT, GNSS_STATE_PIN, tracking ? GPIO_PIN_SET: GPIO_PIN_RESET);
|
||||
}
|
||||
|
||||
extern "C"
|
||||
{
|
||||
|
||||
void USART1_IRQHandler(void)
|
||||
{
|
||||
if ( __HAL_UART_GET_IT(&huart1, UART_IT_RXNE) )
|
||||
{
|
||||
__HAL_UART_CLEAR_IT(&huart1, UART_IT_RXNE);
|
||||
char c = USART1->RDR;
|
||||
if ( terminalInputCallback )
|
||||
terminalInputCallback(c);
|
||||
}
|
||||
}
|
||||
|
||||
void EXTI2_IRQHandler(void)
|
||||
{
|
||||
if ( __HAL_GPIO_EXTI_GET_IT(GPIO_PIN_2) != RESET )
|
||||
{
|
||||
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_2);
|
||||
if ( ppsCallback )
|
||||
ppsCallback();
|
||||
}
|
||||
}
|
||||
|
||||
void USART2_IRQHandler()
|
||||
{
|
||||
if ( __HAL_UART_GET_IT(&huart2, UART_IT_RXNE) )
|
||||
{
|
||||
__HAL_UART_CLEAR_IT(&huart2, UART_IT_RXNE);
|
||||
char c = (char)USART2->RDR;
|
||||
if ( gnssInputCallback )
|
||||
gnssInputCallback(c);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void TIM2_IRQHandler(void)
|
||||
{
|
||||
if(__HAL_TIM_GET_FLAG(&htim2, TIM_FLAG_UPDATE) != RESET)
|
||||
{
|
||||
if(__HAL_TIM_GET_IT_SOURCE(&htim2, TIM_IT_UPDATE) !=RESET)
|
||||
{
|
||||
__HAL_TIM_CLEAR_IT(&htim2, TIM_IT_UPDATE);
|
||||
if ( sotdmaCallback )
|
||||
sotdmaCallback();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void EXTI3_IRQHandler(void)
|
||||
{
|
||||
if ( __HAL_GPIO_EXTI_GET_IT(GPIO_PIN_3) != RESET )
|
||||
{
|
||||
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_3);
|
||||
if ( rxClockCallback )
|
||||
rxClockCallback();
|
||||
}
|
||||
}
|
||||
|
||||
void EXTI15_10_IRQHandler(void)
|
||||
{
|
||||
if ( __HAL_GPIO_EXTI_GET_IT(GPIO_PIN_15) != RESET )
|
||||
{
|
||||
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_15);
|
||||
if ( trxClockCallback )
|
||||
trxClockCallback();
|
||||
}
|
||||
}
|
||||
|
||||
void HAL_SYSTICK_Callback()
|
||||
{
|
||||
static int count = 1;
|
||||
if ( count++ % 20 == 0 )
|
||||
{
|
||||
count = 1;
|
||||
HAL_GPIO_WritePin(RX_EVT_PORT, RX_EVT_PIN, GPIO_PIN_RESET);
|
||||
HAL_GPIO_WritePin(TX_EVT_PORT, TX_EVT_PIN, GPIO_PIN_RESET);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
#endif
|
18
latest/Firmware/Src/si4460.cpp
Normal file
18
latest/Firmware/Src/si4460.cpp
Normal file
@ -0,0 +1,18 @@
|
||||
/*
|
||||
* si4460.cpp
|
||||
*
|
||||
* Created on: Mar 13, 2021
|
||||
* Author: peter
|
||||
*/
|
||||
|
||||
|
||||
#include <stdint.h>
|
||||
#include "radio_config_si4460.h"
|
||||
|
||||
|
||||
static uint8_t __si_4460_cfg[] = RADIO_CONFIGURATION_DATA_ARRAY;
|
||||
|
||||
uint8_t* get_si4460_config_array()
|
||||
{
|
||||
return __si_4460_cfg;
|
||||
}
|
Loading…
x
Reference in New Issue
Block a user