Fix issues with firmware heap and stack colliding. Refactor radio transmission code into multiples files. Add more data from GPS to APRS packets. Get more data from GPS (climb/course). Implement simple GPS time-based scheduling of digital modes that require accurate timing. Write some initial documentation for building/flashing the firmware.

main
Mikael Nousiainen 2020-09-03 22:12:43 +03:00
rodzic 105149c186
commit 4714911e35
33 zmienionych plików z 1759 dodań i 1272 usunięć

155
README.md
Wyświetl plik

@ -10,21 +10,149 @@ The motivation to develop this firmware is to provide cleaner, customizable and
more modular codebase for developing RS41 radiosonde-based experiments.
The main features this firmware aims to implement are:
* DMA/Timer-based modulation for APRS and many digital modes via JTEncode library
* Support for HF/VHF transmissions via an external Si5351 chip connected to the external I²C bus
* Enhanced support for the internal Si4032 radio transmitter via PWM-based tone generation (and ultimately DMA-based symbol timing, if possible)
* Support for additional digital modes on HF/VHF amateur radio bands using an external Si5351 clock generator connected to the external I²C bus
* Support for custom sensors via the external I²C bus
* Extensibility to allow easy addition of new digital modes
## Features (work in progress)
## Features currently working
* APRS on 70cm amateur radio band via Si4032 radio chip
* Bell 202 timing is done via DMA transfers to achieve greater accuracy, but I have not been able to get the timings working correctly
* Digital mode beacons on HF frequencies via a Si5351 radio chip connected to the external I²C bus of the RS41 radiosonde
* APRS on 70cm amateur radio band using the internal Si4032 radio transmitter
* Bell 202 frequencies are generated via hardware PWM, but the symbol timing is created in a loop with delay
* There is also code available to use DMA transfers for symbol timing to achieve greater accuracy, but I have not been able to get the timings working correctly
* Digital mode beacons on HF/VHF frequencies using a Si5351 clock generator connected to the external I²C bus of the RS41 radiosonde
* The JTEncode library provides JT65/JT9/JT4/FT8/WSPR/FSQ beacon transmissions. I've decoded FT8 and WSPR successfully.
The implementation is missing correct scheduling of transmissions via GPS clock.
* Support for additional sensors via the external I²C bus
* There is a driver for Bosch BMP280 barometric pressure / temperature / humidity sensor included
* GPS-based scheduling is available for modes that require specific timing for transmissions
* *NOTE:* It is most likely not possible to implement 1200 bps Bell 202 modulation for APRS using Si5351,
because the Si5351 chip is too slow to change the generated frequency
* External I²C bus sensor drivers
* Bosch BMP280 barometric pressure / temperature / humidity sensor
### Bell FSK modulation hack for APRS
### Planned features
* CW (on-off keying) on both Si4032 (70cm) and Si5351 (HF + 2m)
* RTTY on both Si4032 (70cm, non-standard shift) and Si5351 (HF + 2m) with configurable shift
* Support for more I²C sensors
* Configurable transmission frequencies and schedules based on location / altitude
## Building the firmware
Software requirements:
* [GNU GCC toolchain](https://developer.arm.com/tools-and-software/open-source-software/developer-tools/gnu-toolchain/gnu-a/downloads/9-2-2019-12)
version 8.3.0 or higher for cross-compiling the firmware for the ARM Cortex-M3 architecture (`arm-none-eabi-gcc`)
* [CMake](https://cmake.org/) version 3.6 or higher for building the firmware
* [OpenOCD](http://openocd.org/) version 0.10.0 or higher for flashing the firmware
On a Red Hat/Fedora Linux installation, the following packages can be installed:
```bash
dnf install arm-none-eabi-gcc-cs arm-none-eabi-gcc-cs-c++ arm-none-eabi-binutils-cs arm-none-eabi-newlib cmake openocd
```
### Steps to build the firmware
1. Install the required software dependencies listed above
2. Configure your amateur radio call sign, transmit frequencies and transmission mode parameters in `config.h`
3. Configure scheduling of transmissions in `radio.c` by editing array `radio_transmit_schedule`
4. Build the firmware using the following commands
```
mkdir build
cd build
cmake ..
make
```
3. The firmware will be stored in file `build/src/RS41ng.elf`
## Flashing the firmware
Hardware requirements:
* A working Vaisala RS41 radiosonde :)
* A programmer for the STM32 microcontroller present in the RS41 radiosonde. ST-LINK v2 USB-dongles work well.
The pinout of the RS41 connector (by DF8OE) is the following:
```
______________________| |______________________
| |
| 1 2 3 4 5 |
| |
| 6 7 8 9 10 |
|_______________________________________________________|
(View from the bottom of the sonde, pay attention to the gap in the connector)
```
* 1 - SWDIO (PA13)
* 2 - RST
* 3 - MCU switched 3.3V out to external device / Vcc (Boost out) 5.0V
-- This pin powers the device via 3.3V from an ST-LINK programmer dongle
* 4 - I2C2_SCL (PB10) / UART3 TX -- This is the external I²C port clock pin for Si5351 and sensors
* 5 - GND
* 6 - GND
* 7 - SWCLK (PA14)
* 8 - +U_Battery / VBAT 3.3V
* 9 - +VDD_MCU / PB1 * (10k + cap + 10k)
* 10 - I2C2_SDA (PB11) / UART3 RX -- This is the external I²C port data pin for Si5351 and sensors
### Steps to flash the firmware
1. Remove batteries from the sonde
2. Connect an ST-LINK v2 programmer dongle to the sonde via the following pins:
* SWDIO -> Pin 1
* SWCLK -> Pin 7
* GND -> Pin 5
* 3.3V -> Pin 3
3. Unlock the flash protection - needed only before reprogramming the sonde for the first time
* `openocd -f ./openocd_rs41.cfg -c "init; halt; flash protect 0 0 64 off; exit"`
4. Flash the firmware
* `openocd -f ./openocd_rs41.cfg -c "program build/src/RS41ng.elf verify reset exit"`
5. Power cycle the sonde to start running the new firmware
## Developing / debugging the firmware
It is possible to receive log messages from the firmware program and to perform debugging of the firmware using GNU GDB.
Also, please note that Red Hat/Fedora do not provide GDB for ARM architectures, so you will need to manually download
and install GDB from [ARM GNU GCC toolchain](https://developer.arm.com/tools-and-software/open-source-software/developer-tools/gnu-toolchain/gnu-a/downloads/9-2-2019-12).
Semihosting allows the firmware to send log messages via special system calls to OpenOCD, so that you
can get real-time feedback and debug output from the application.
*Semihosting needs to be disabled when not connec
### Steps to start firmware debugging and semihosting
1. Connect the RS41 radiosonde to a computer via the STM32 ST-LINK programmer dongle
2. Enable semihosting and logging in `config.h` by uncommenting the following lines
```
#define SEMIHOSTING_ENABLE
#define LOGGING_ENABLE
```
3. Start OpenOCD and leave it running in the background
```
openocd -f ./openocd_rs41.cfg
```
4. Start ARM GDB
```
arm-none-eabi-gdb
```
5. Connect GDB to OpenOCD for flashing and debugging (assumes you are in the `build` directory with Makefiles from CMake ready for build)
```
target remote localhost:3333
monitor arm semihosting enable
make
load src/RS41ng.elf
monitor reset halt
continue # this command runs the firmware
```
6. OpenOCD will output log messages from the firmware and GDB can be used to interrupt
and inspect the firmware program.
To load debugging symbols for settings breakpoints and to perform more detailed inspection,
use command `file src/RS41ng.elf`.
## Si4032 Bell FSK modulation hack for APRS
The idea behind the APRS / Bell 202 modulation implementation is based on RS41HUP project and its "ancestors"
and I'm describing it here, since it has not been documented elsewhere.
@ -39,11 +167,14 @@ a rate of 1200 and 2200 Hz, which produces the two Bell 202 tones even though th
Additionally, the timing of 1200/2200 Hz was done in RS41HUP by using experimentally determined delays
and by disabling all interrupts, so they won't interfere with the timings.
I have attempted to implement Bell 202 frequency generation using DMA / Timers, but have failed to generate correct
frequencies that other APRS equipment are able to decode. I have tried to decode the DMA-based modulation with
I have attempted to implement Bell 202 frequency generation using hardware DMA and PWM, but have failed to generate
correct symbol rate that other APRS equipment are able to decode. I have tried to decode the DMA-based modulation with
some tools intended for debugging APRS and while some bytes are decoded correctly every once in a while,
the timings are mostly off for some unknown reason.
Currently, the Bell 202 modulation implementation uses hardware PWM to generate the individual tone frequencies,
but the symbol timing is created in a loop with delay that was chosen carefully via experiments.
# Authors
* Authors of the [RS41HUP](https://github.com/df8oe/RS41HUP) project

Wyświetl plik

@ -1,26 +0,0 @@
Created by DF8OE
----------------
view into port from outside
______________________| |______________________
| |
| 1 2 3 4 5 |
| |
| 6 7 8 9 10 |
|_______________________________________________________|
1 - SWDIO (PA13)
2 - RST
3 - MCU switched 3.3V out to external device / Vcc (Boost out) 5.0V (powers the device via 3.3V)
4 - I2C2_SCL (PB10) / UART3 TX
5 - GND
6 - GND
7 - SWCLK (PA14)
8 - +U_Battery / VBAT 3.3V
9 - +VDD_MCU / PB1 * (10k + cap + 10k)
10 - I2C2_SDA (PB11) / UART3 RX

Wyświetl plik

@ -19,12 +19,12 @@ add_definitions(-DSUPPORT_CPLUSPLUS)
add_definitions(-D__ASSEMBLY__)
SET(LINKER_SCRIPT arm-gcc-link.ld)
SET(COMMON_FLAGS " -mcpu=cortex-m3 -mthumb -Wall -ffunction-sections -g -O3 -nostartfiles ")
SET(COMMON_FLAGS " -mcpu=cortex-m3 -mthumb -Wall -ffunction-sections -fdata-sections -g -O3 -nostartfiles")
SET(CMAKE_CXX_FLAGS "${COMMON_FLAGS} -std=c++11")
SET(CMAKE_C_FLAGS "${COMMON_FLAGS} -std=gnu99")
SET(CMAKE_EXE_LINKER_FLAGS "-Wl,-Map=${CMAKE_BINARY_DIR}/${PROJECT_NAME}.map -lstdc++ -O3 -Wl,--gc-sections --specs=nano.specs -T ${LINKER_SCRIPT}")
SET(CMAKE_C_FLAGS "${COMMON_FLAGS} -std=gnu99 -Dprintf=iprintf")
SET(CMAKE_EXE_LINKER_FLAGS "-Wl,-Map=${CMAKE_BINARY_DIR}/${PROJECT_NAME}.map -lstdc++ -O3 -Dprintf=iprintf -mcpu=cortex-m3 -mthumb -Wl,--gc-sections --specs=nano.specs -T ${LINKER_SCRIPT}")
# -u _printf_float
#SET(CMAKE_EXE_LINKER_FLAGS "-Wl,-Map=${CMAKE_BINARY_DIR}/${PROJECT_NAME}.map -lstdc++ -O3 -Wl,--gc-sections --specs=rdimon.specs -lc -lrdimon -T ${LINKER_SCRIPT}")
#SET(CMAKE_EXE_LINKER_FLAGS "-Wl,-Map=${CMAKE_BINARY_DIR}/${PROJECT_NAME}.map -lstdc++ -O3 -mcpu=cortex-m3 -mthumb -Wl,--gc-sections --specs=rdimon.specs -lc -lrdimon -T ${LINKER_SCRIPT}")
file(GLOB_RECURSE USER_SOURCES "*.c")
file(GLOB_RECURSE USER_SOURCES_CXX "*.cpp")
@ -37,7 +37,6 @@ include_directories(hal/cmsis
add_executable(${PROJECT_NAME}.elf ${USER_SOURCES} ${USER_SOURCES_CXX} ${USER_HEADERS} ${HAL_SOURCES} ${LINKER_SCRIPT})
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -Wl,-Map=${CMAKE_BINARY_DIR}/${PROJECT_NAME}.map")
set(HEX_FILE ${CMAKE_BINARY_DIR}/${PROJECT_NAME}.hex)
set(BIN_FILE ${CMAKE_BINARY_DIR}/${PROJECT_NAME}.bin)
add_custom_command(TARGET ${PROJECT_NAME}.elf POST_BUILD

Wyświetl plik

@ -1,132 +1,146 @@
OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
/* Internal Memory Map*/
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 0x00010000
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00002000
}
_eram = 0x20000000 + 0x00002000;
SECTIONS
{
.text :
{
KEEP(*(.isr_vector))
*(.text*)
KEEP(*(.init))
KEEP(*(.fini))
/* .ctors */
*crtbegin.o(.ctors)
*crtbegin?.o(.ctors)
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
*(SORT(.ctors.*))
*(.ctors)
/* .dtors */
*crtbegin.o(.dtors)
*crtbegin?.o(.dtors)
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
*(SORT(.dtors.*))
*(.dtors)
*(.rodata*)
KEEP(*(.eh_fram e*))
} > rom
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > rom
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
} > rom
__exidx_end = .;
__etext = .;
/* _sidata is used in coide startup code */
_sidata = __etext;
.data : AT (__etext)
{
__data_start__ = .;
/* _sdata is used in coide startup code */
_sdata = __data_start__;
*(vtable)
*(.data*)
. = ALIGN(8);
/* preinit data */
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP(*(.preinit_array))
PROVIDE_HIDDEN (__preinit_array_end = .);
. = ALIGN(8);
/* init data */
PROVIDE_HIDDEN (__init_array_start = .);
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
PROVIDE_HIDDEN (__init_array_end = .);
. = ALIGN(8);
/* finit data */
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP(*(SORT(.fini_array.*)))
KEEP(*(.fini_array))
PROVIDE_HIDDEN (__fini_array_end = .);
KEEP(*(.jcr*))
. = ALIGN(8);
/* All data end */
__data_end__ = .;
/* _edata is used in coide startup code */
_edata = __data_end__;
} > ram
.bss :
{
. = ALIGN(8);
__bss_start__ = .;
_sbss = __bss_start__;
*(.bss*)
*(COMMON)
. = ALIGN(8);
__bss_end__ = .;
_ebss = __bss_end__;
} > ram
.heap (COPY):
{
__end__ = .;
_end = __end__;
end = __end__;
*(.heap*)
__HeapLimit = .;
} > ram
/* .stack_dummy section doesn't contains any symbols. It is only
* used for linker to calculate size of stack sections, and assign
* values to stack symbols later */
.co_stack (NOLOAD):
{
. = ALIGN(8);
*(.co_stack .co_stack.*)
} > ram
/* Set stack top to end of ram , and stack limit move down by
* size of stack_dummy section */
__StackTop = ORIGIN(ram ) + LENGTH(ram );
__StackLimit = __StackTop - SIZEOF(.co_stack);
PROVIDE(__stack = __StackTop);
/* Check if data + heap + stack exceeds ram limit */
ASSERT(__StackLimit >= __HeapLimit, "region ram overflowed with stack")
}
OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
/* Internal Memory Map*/
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 0x00010000
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00002000
}
_eram = 0x20000000 + 0x00002000;
__HeapSize = 0x800;
SECTIONS
{
.text :
{
KEEP(*(.isr_vector))
*(.text*)
KEEP(*(.init))
KEEP(*(.fini))
/* .ctors */
*crtbegin.o(.ctors)
*crtbegin?.o(.ctors)
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
*(SORT(.ctors.*))
*(.ctors)
/* .dtors */
*crtbegin.o(.dtors)
*crtbegin?.o(.dtors)
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
*(SORT(.dtors.*))
*(.dtors)
*(.rodata*)
KEEP(*(.eh_fram e*))
} > rom
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > rom
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
} > rom
__exidx_end = .;
__etext = .;
/* _sidata is used in coide startup code */
_sidata = __etext;
.data : AT (__etext)
{
__data_start__ = .;
/* _sdata is used in coide startup code */
_sdata = __data_start__;
*(vtable)
*(.data*)
. = ALIGN(8);
/* preinit data */
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP(*(.preinit_array))
PROVIDE_HIDDEN (__preinit_array_end = .);
. = ALIGN(8);
/* init data */
PROVIDE_HIDDEN (__init_array_start = .);
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
PROVIDE_HIDDEN (__init_array_end = .);
. = ALIGN(8);
/* finit data */
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP(*(SORT(.fini_array.*)))
KEEP(*(.fini_array))
PROVIDE_HIDDEN (__fini_array_end = .);
KEEP(*(.jcr*))
. = ALIGN(8);
/* All data end */
__data_end__ = .;
/* _edata is used in coide startup code */
_edata = __data_end__;
} > ram
.bss :
{
. = ALIGN(8);
__bss_start__ = .;
_sbss = __bss_start__;
*(.bss*)
*(COMMON)
. = ALIGN(8);
__bss_end__ = .;
_ebss = __bss_end__;
} > ram
.heap :
{
. = ALIGN(8);
__HeapStart = .;
__end__ = .;
_end = __end__;
end = __end__;
*(.heap*)
. = . + __HeapSize;
__HeapLimit = .;
} > ram
/* .co_stack section doesn't contains any symbols. It is only
* used for linker to calculate size of stack sections, and assign
* values to stack symbols later */
.co_stack (NOLOAD):
{
. = ALIGN(8);
__StackStart = .;
*(.co_stack .co_stack.*)
. = ALIGN(8);
__StackEnd = .;
} > ram
/* NOTE: These variables don't seem to affect anything.
*
* Set stack top to end of ram , and stack limit move down by
* size of co_stack section */
__StackTop = ORIGIN(ram) + LENGTH(ram);
__StackLimit = __StackTop - SIZEOF(.co_stack);
PROVIDE(__stack = __StackTop);
/* Check if data + heap + stack exceeds ram limit */
ASSERT(__StackLimit >= __HeapLimit, "region ram overflowed with stack")
.last_section (NOLOAD):
{
. = ALIGN(8);
} > ram
}

Wyświetl plik

@ -1,5 +1,6 @@
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include "aprs.h"
/**
@ -28,67 +29,47 @@ static void convert_degrees_to_dmh(long x, int8_t *degrees, uint8_t *minutes, ui
}
}
size_t aprs_generate_position_without_timestamp(uint8_t *payload, size_t length, telemetry_data *data,
char symbol_table, char symbol, char *comment)
size_t aprs_generate_position(uint8_t *payload, size_t length, telemetry_data *data,
char symbol_table, char symbol, bool include_timestamp, char *comment)
{
char timestamp[12];
int8_t la_degrees, lo_degrees;
uint8_t la_minutes, la_h_minutes, lo_minutes, lo_h_minutes;
convert_degrees_to_dmh(data->gps.lat_raw / 10, &la_degrees, &la_minutes, &la_h_minutes);
convert_degrees_to_dmh(data->gps.lon_raw / 10, &lo_degrees, &lo_minutes, &lo_h_minutes);
convert_degrees_to_dmh(data->gps.latitude_degrees_1000000 / 10, &la_degrees, &la_minutes, &la_h_minutes);
convert_degrees_to_dmh(data->gps.longitude_degrees_1000000 / 10, &lo_degrees, &lo_minutes, &lo_h_minutes);
int16_t heading_degrees = (int16_t) ((float) data->gps.heading_degrees_100000 / 100000.0f);
int16_t ground_speed_knots = (int16_t) (((float) data->gps.ground_speed_cm_per_second / 100.0f) * 3.6f / 1.852f);
int32_t altitude_feet = (data->gps.altitude_mm / 1000) * 3280 / 1000;
if (include_timestamp) {
snprintf(timestamp, sizeof(timestamp), "/%02d%02d%02dz", data->gps.hours, data->gps.minutes, data->gps.seconds);
} else {
strncpy(timestamp, "!", sizeof(timestamp));
}
aprs_packet_counter++;
return snprintf((char *) payload,
length,
("!%02d%02d.%02u%c%c%03d%02u.%02u%c%c%03d/%03d/A=%06ld/P%dS%dT%ldV%dC%d%s"),
("%s%02d%02d.%02u%c%c%03d%02u.%02u%c%c%03d/%03d/A=%06ld/P%dS%dT%02ldV%04dC%02d%s"),
timestamp,
abs(la_degrees), la_minutes, la_h_minutes,
la_degrees > 0 ? 'N' : 'S',
symbol_table,
abs(lo_degrees), lo_minutes, lo_h_minutes,
lo_degrees > 0 ? 'E' : 'W',
symbol,
(int16_t) ((float) data->gps.heading_raw / 100000.0f),
(int16_t) (((float) data->gps.speed_raw / 100.0f) * 3.6f / 1.852f),
(data->gps.alt_raw / 1000) * 3280 / 1000,
heading_degrees,
ground_speed_knots,
altitude_feet,
aprs_packet_counter,
data->gps.sats_raw,
data->internal_temperature_celsius_100 / 10,
data->gps.satellites_visible,
data->internal_temperature_celsius_100 / 100,
data->battery_voltage_millivolts,
(int16_t) ((float) data->gps.climb_raw / 100.0f),
comment
);
}
size_t aprs_generate_position_with_timestamp(uint8_t *payload, size_t length, telemetry_data *data,
char symbol_table, char symbol, char *comment)
{
int8_t la_degrees, lo_degrees;
uint8_t la_minutes, la_h_minutes, lo_minutes, lo_h_minutes;
convert_degrees_to_dmh(data->gps.lat_raw / 10, &la_degrees, &la_minutes, &la_h_minutes);
convert_degrees_to_dmh(data->gps.lon_raw / 10, &lo_degrees, &lo_minutes, &lo_h_minutes);
aprs_packet_counter++;
return snprintf((char *) payload,
length,
("/%02d%02d%02dz%02d%02d.%02u%c%c%03d%02u.%02u%c%c%03d/%03d/A=%06ld/P%dS%dT%ldV%dC%d%s"),
data->gps.hours, data->gps.minutes, data->gps.seconds,
abs(la_degrees), la_minutes, la_h_minutes,
la_degrees > 0 ? 'N' : 'S',
symbol_table,
abs(lo_degrees), lo_minutes, lo_h_minutes,
lo_degrees > 0 ? 'E' : 'W',
symbol,
(int16_t) ((float) data->gps.heading_raw / 100000.0f),
(int16_t) (((float) data->gps.speed_raw / 100.0f) * 3.6f / 1.852f),
(data->gps.alt_raw / 1000) * 3280 / 1000,
aprs_packet_counter,
data->gps.sats_raw,
data->internal_temperature_celsius_100 / 10,
data->battery_voltage_millivolts,
(int16_t) ((float) data->gps.climb_raw / 100.0f),
(int16_t) ((float) data->gps.climb_cm_per_second / 100.0f),
comment
);
}

Wyświetl plik

@ -7,7 +7,7 @@
#include "gps.h"
#include "telemetry.h"
size_t aprs_generate_position_without_timestamp(uint8_t *payload, size_t length, telemetry_data *data,
char symbol_table, char symbol, char *comment);
size_t aprs_generate_position(uint8_t *payload, size_t length, telemetry_data *data,
char symbol_table, char symbol, bool include_timestamp, char *comment);
#endif

Wyświetl plik

@ -1,6 +1,8 @@
#ifndef __FSK_H
#define __FSK_H
#define FSK_TONE_COUNT_MAX 20
typedef struct _fsk_tone {
int8_t index;
uint32_t frequency_hz_100;

Wyświetl plik

@ -63,8 +63,6 @@
#define JTENCODE_TONE_DELAY_FSQ_4_5 222 * 100 // Delay value for 4.5 baud FSQ
#define JTENCODE_TONE_DELAY_FSQ_6 167 * 100 // Delay value for 6 baud FSQ
#define JTENCODE_SYMBOL_BUFFER_LENGTH 512
typedef struct _jtencode_mode {
uint16_t symbol_count;
uint32_t tone_delay_ms_100;
@ -135,19 +133,30 @@ typedef struct _jtencode_encoder {
uint32_t tone_spacing;
uint32_t tone_delay;
uint8_t symbol_data[JTENCODE_SYMBOL_BUFFER_LENGTH];
size_t symbol_data_length;
uint8_t *symbol_data;
size_t current_byte_index;
} jtencode_encoder;
void jtencode_encoder_new(fsk_encoder *encoder, jtencode_mode_type mode_type, char *wspr_callsign, char *wspr_locator, uint8_t wspr_dbm,
bool jtencode_encoder_new(fsk_encoder *encoder, size_t symbol_data_length, uint8_t *symbol_data,
jtencode_mode_type mode_type, char *wspr_callsign, char *wspr_locator, uint8_t wspr_dbm,
char *fsq_callsign_from, char *fsq_callsign_to, char fsq_command)
{
jtencode_mode_descriptor *mode_descriptor = &jtencode_modes[mode_type];
if (mode_descriptor->symbol_count > 0) {
if (mode_descriptor->symbol_count > symbol_data_length) {
return false;
}
}
encoder->priv = malloc(sizeof(jtencode_encoder));
memset(encoder->priv, 0, sizeof(jtencode_encoder));
jtencode_mode_descriptor *mode_descriptor = &jtencode_modes[mode_type];
auto *jte = (jtencode_encoder *) encoder->priv;
jte->symbol_data_length = symbol_data_length;
jte->symbol_data = symbol_data;
jte->mode_type = mode_type;
jte->symbol_count = mode_descriptor->symbol_count;
jte->tone_spacing = mode_descriptor->tone_spacing_hz_100;
@ -160,6 +169,8 @@ void jtencode_encoder_new(fsk_encoder *encoder, jtencode_mode_type mode_type, ch
jte->fsq_callsign_from = fsq_callsign_from;
jte->fsq_callsign_to = fsq_callsign_to;
jte->fsq_command = fsq_command;
return true;
}
void jtencode_encoder_destroy(fsk_encoder *encoder)
@ -200,7 +211,7 @@ void jtencode_encoder_set_data(fsk_encoder *encoder, uint16_t data_length, uint8
uint8_t *symbol_data = jte->symbol_data;
jtencode_mode_type mode_type = jte->mode_type;
memset(symbol_data, 0, JTENCODE_SYMBOL_BUFFER_LENGTH);
memset(symbol_data, 0, jte->symbol_data_length);
switch (mode_type) {
case JTENCODE_MODE_JT9:
@ -240,7 +251,6 @@ int8_t jtencode_encoder_next_tone(fsk_encoder *encoder)
size_t current_byte_index = jte->current_byte_index;
if (current_byte_index >= jte->symbol_count) {
log_info("last tone: %d\n", current_byte_index);
return -1;
}

Wyświetl plik

@ -1,6 +1,8 @@
#ifndef __JTENCODE_H
#define __JTENCODE_H
#include "codecs/fsk/fsk.h"
#ifdef __cplusplus
extern "C" {
#endif
@ -17,7 +19,8 @@ typedef enum _jtencode_mode_type {
JTENCODE_MODE_FSQ_6,
} jtencode_mode_type;
void jtencode_encoder_new(fsk_encoder *encoder, jtencode_mode_type mode_type, char *wspr_callsign, char *wspr_locator, uint8_t wspr_dbm,
bool jtencode_encoder_new(fsk_encoder *encoder, size_t symbol_data_length, uint8_t *symbol_data,
jtencode_mode_type mode_type, char *wspr_callsign, char *wspr_locator, uint8_t wspr_dbm,
char *fsq_callsign_from, char *fsq_callsign_to, char fsq_command);
void jtencode_encoder_destroy(fsk_encoder *encoder);

Wyświetl plik

@ -3,17 +3,20 @@
// Enable semihosting to receive debug logs during development
//#define SEMIHOSTING_ENABLE
//#define LOGGING_ENABLE
#include <stdbool.h>
#define RADIO_PAYLOAD_MAX_LENGTH 384
#define RADIO_PAYLOAD_MAX_LENGTH 256
#define RADIO_SYMBOL_DATA_MAX_LENGTH 512
#define APRS_COMMENT_MAX_LENGTH 128
#define SENSOR_BMP280_ENABLE false
#define RADIO_SI5351_ENABLE true
#define RADIO_POST_TRANSMIT_DELAY 5000
#define RADIO_POST_TRANSMIT_DELAY_MS 5000
#define RADIO_TIME_SYNC_THRESHOLD_MS 1500
// Si4032 transmit power: 0..100%
#define RADIO_SI4032_TX_POWER 100
@ -32,11 +35,13 @@
#define LOCATOR_PAIR_COUNT_FULL 6 // max. 6 (12 characters WWL)
#define WSPR_CALLSIGN "OH3BHX"
//#define WSPR_LOCATOR_FIXED "AA00"
#define WSPR_LOCATOR_FIXED_ENABLED false
#define WSPR_LOCATOR_FIXED "AA00"
#define WSPR_DBM 10
#define FT8_CALLSIGN "OH3BHX"
//#define FT8_LOCATOR_FIXED "AA00"
#define FT8_LOCATOR_FIXED_ENABLED false
#define FT8_LOCATOR_FIXED "AA00"
#define FSQ_CALLSIGN_FROM "OH3BHX"
#define FSQ_CALLSIGN_TO "N0CALL"

Wyświetl plik

@ -130,8 +130,6 @@ static int write_register8(bmp280 *dev, uint8_t reg, uint8_t value)
return true;
}
#include <stdio.h>
bool bmp280_init(bmp280 *dev, bmp280_params_t *params)
{
if (dev->addr != BMP280_I2C_ADDRESS_0
@ -140,27 +138,19 @@ bool bmp280_init(bmp280 *dev, bmp280_params_t *params)
return false;
}
printf("bmp280 0\n");
if (!read_data(dev, BMP280_REG_ID, &dev->id, 1)) {
return false;
}
printf("bmp280 1\n");
if (dev->id != BMP280_CHIP_ID && dev->id != BME280_CHIP_ID) {
return false;
}
printf("bmp280 1.5\n");
// Soft reset.
if (!write_register8(dev, BMP280_REG_RESET, BMP280_RESET_VALUE)) {
return false;
}
printf("bmp280 2\n");
// Wait until finished copying over the NVP data.
while (1) {
uint8_t status;

Wyświetl plik

@ -444,7 +444,7 @@ void Si5351::set_pll(uint64_t pll_freq, enum si5351_pll target_pll)
// Derive the register values to write
// Prepare an array for parameters to be written to
uint8_t *params = new uint8_t[20];
uint8_t params[20];
uint8_t i = 0;
uint8_t temp;
@ -486,8 +486,6 @@ void Si5351::set_pll(uint64_t pll_freq, enum si5351_pll target_pll)
si5351_write_bulk(SI5351_PLLB_PARAMETERS, i, params);
pllb_freq = pll_freq;
}
delete params;
}
/*
@ -506,7 +504,7 @@ void Si5351::set_pll(uint64_t pll_freq, enum si5351_pll target_pll)
void
Si5351::set_ms(enum si5351_clock clk, struct Si5351RegSet ms_reg, uint8_t int_mode, uint8_t r_div, uint8_t div_by_4)
{
uint8_t *params = new uint8_t[20];
uint8_t params[20];
uint8_t i = 0;
uint8_t temp;
uint8_t reg_val;
@ -590,8 +588,6 @@ Si5351::set_ms(enum si5351_clock clk, struct Si5351RegSet ms_reg, uint8_t int_mo
ms_div(clk, r_div, div_by_4);
break;
}
delete params;
}
/*
@ -1075,7 +1071,7 @@ void Si5351::set_vcxo(uint64_t pll_freq, uint8_t ppm)
// Derive the register values to write
// Prepare an array for parameters to be written to
uint8_t *params = new uint8_t[20];
uint8_t params[20];
uint8_t i = 0;
uint8_t temp;
@ -1112,8 +1108,6 @@ void Si5351::set_vcxo(uint64_t pll_freq, uint8_t ppm)
// Write the parameters
si5351_write_bulk(SI5351_PLLB_PARAMETERS, i, params);
delete params;
// Write the VCXO parameters
vcxo_param = ((vcxo_param * ppm * SI5351_VCXO_MARGIN) / 100ULL) / 1000000ULL;

Wyświetl plik

@ -7,8 +7,218 @@
#include "ubxg6010.h"
#include "log.h"
typedef struct __attribute__((packed)) {
uint8_t sc1; // 0xB5
uint8_t sc2; // 0x62
uint8_t messageClass;
uint8_t messageId;
uint16_t payloadSize;
} uBloxHeader;
typedef struct {
uint8_t ck_a;
uint8_t ck_b;
} uBloxChecksum;
typedef struct {
uint32_t iTOW; //GPS time of week of the navigation epoch. [- ms]
uint16_t year; //Year (UTC) [- y]
uint8_t month; //Month, range 1..12 (UTC) [- month]
uint8_t day; //Day of month, range 1..31 (UTC) [- d]
uint8_t hour; //Hour of day, range 0..23 (UTC) [- h]
uint8_t min; //Minute of hour, range 0..59 (UTC) [- min]
uint8_t sec; //Seconds of minute, range 0..60 (UTC) [- s]
uint8_t valid; //Validity flags (see graphic below) [- -]
uint32_t tAcc; //Time accuracy estimate (UTC) [- ns]
int32_t nano; //Fraction of second, range -1e9 .. 1e9 (UTC) [- ns]
uint8_t fixType; //GNSSfix Type: [- -]
uint8_t flags; //Fix status flags (see graphic below) [- -]
uint8_t flags2; //Additional flags (see graphic below) [- -]
uint8_t numSV; //Number of satellites used in Nav Solution [- -]
int32_t lon; //Longitude [1e-7 deg]
int32_t lat; //Latitude [1e-7 deg]
int32_t height; //Height above ellipsoid [- mm]
int32_t hMSL; //Height above mean sea level [- mm]
uint32_t hAcc; //Horizontal accuracy estimate [- mm]
uint32_t vAcc; //Vertical accuracy estimate [- mm]
int32_t velN; //NED north velocity [- mm/s]
int32_t velE; //NED east velocity [- mm/s]
int32_t velD; //NED down velocity [- mm/s]
int32_t gSpeed; //Ground Speed (2-D) [- mm/s]
int32_t headMot; //Heading of motion (2-D) [1e-5 deg]
uint32_t sAcc; //Speed accuracy estimate [- mm/s]
uint32_t headAcc; //Heading accuracy estimate (both motion and vehicle) [1e-5 deg]
uint16_t pDOP; //Position DOP [0.01 -]
uint8_t reserved1[6]; //Reserved [- -]
int32_t headVeh; //Heading of vehicle (2-D) [1e-5 deg]
uint8_t reserved2[4]; //Reserved [- -]
} uBloxNAVPVTPayload;
typedef struct {
uint32_t iTOW; //GPS Millisecond Time of Week [- ms]
int32_t lon; //Longitude [1e-7 deg]
int32_t lat; //Latitude [1e-7 deg]
int32_t height; //Height above Ellipsoid [- mm]
int32_t hMSL; //Height above mean sea level [- mm]
uint32_t hAcc; //Horizontal Accuracy Estimate [- mm]
uint32_t vAcc; //Vertical Accuracy Estimate [- mm]
} uBloxNAVPOSLLHPayload;
typedef struct {
uint32_t iTOW; //GPS Millisecond Time of Week [- ms]
int32_t fTOW; //Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000 [- ns]
int16_t week; //GPS week (GPS time) [- -]
uint8_t gpsFix; //GPSfix Type, range 0..5 0x00 = No Fix 0x01 = Dead Reckoning only 0x02 = 2D-Fix 0x03 = 3D-Fix 0x04 = GPS + dead reckoning combined 0x05 = Time only fix 0x06..0xff: reserved [- -]
uint8_t flags; //Fix Status Flags (see graphic below) [- -]
int32_t ecefX; //ECEF X coordinate [- cm]
int32_t ecefY; //ECEF Y coordinate [- cm]
int32_t ecefZ; //ECEF Z coordinate [- cm]
uint32_t pAcc; //3D Position Accuracy Estimate [- cm]
int32_t ecefVX; //ECEF X velocity [- cm/s]
int32_t ecefVY; //ECEF Y velocity [- cm/s]
int32_t ecefVZ; //ECEF Z velocity [- cm/s]
uint32_t sAcc; //Speed Accuracy Estimate [- cm/s]
uint16_t pDOP; //Position DOP [0.01 -]
uint8_t reserved1; //Reserved [- -]
uint8_t numSV; //Number of SVs used in Nav Solution [- -]
uint32_t reserved2; //Reserved [- -]
} uBloxNAVSOLPayload;
typedef struct {
uint32_t iTOW; //GPS Millisecond Time of Week [- ms]
uint32_t fTOW; //Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000 [- ns]
int16_t week; //GPS week (GPS time) [- -]
int8_t leapS; //Leap Seconds (GPS-UTC) [- s]
uint8_t valid; //Validity Flags (see graphic below) [- -]
uint32_t tAcc; //Time Accuracy Estimate [- ns]
} uBloxNAVTIMEGPSPayload;
typedef struct {
uint32_t iTOW; //GPS Millisecond Time of Week [- ms]
uint32_t tAcc; //Time Accuracy Estimate [- ns]
int32_t nano; //Nanoseconds of second, range -1e9 .. 1e9 (UTC) [- ns]
uint16_t year; //Year, range 1999..2099 (UTC) [- y]
uint8_t month; //Month, range 1..12 (UTC) [- month]
uint8_t day; //Day of Month, range 1..31 (UTC) [- d]
uint8_t hour; //Hour of Day, range 0..23 (UTC) [- h]
uint8_t min; //Minute of Hour, range 0..59 (UTC) [- min]
uint8_t sec; //Seconds of Minute, range 0..59 (UTC) [- s]
uint8_t valid; //Validity Flags (see graphic below) [- -]
} uBloxNAVTIMEUTCPayload;
typedef struct {
uint32_t iTOW; //GPS Millisecond Time of Week [- ms]
int32_t velN; //NED north velocity [- cm/s]
int32_t velE; //NED east velocity [- cm/s]
int32_t velD; //NED down velocity [- cm/s]
uint32_t speed; //Speed (3-D) [- cm/s]
uint32_t gSpeed; //Ground Speed (2-D) [- cm/s]
int32_t headMot; //Heading of motion (2-D) [1e-5 deg]
uint32_t sAcc; //Speed accuracy estimate [- cm/s]
uint32_t headAcc; //Heading accuracy estimate (both motion and vehicle) [1e-5 deg]
} uBloxNAVVELNEDPayload;
typedef struct {
uint8_t portID; //Port Identifier Number (see Serial [- -]
uint8_t reserved1; //Reserved [- -]
uint16_t txReady; //TX ready PIN configuration [- -]
uint32_t mode; //A bit mask describing the UART mode [- -]
uint32_t baudRate; //Baud rate in bits/second [- Bits/s]
uint16_t inProtoMask; //A mask describing which input protocols are active. [- -]
uint16_t outProtoMask; //A mask describing which output protocols are active. [- -]
uint16_t flags; //Flags bit mask (see graphic below) [- -]
uint8_t reserved2[2]; //Reserved [- -]
} uBloxCFGPRTPayload;
typedef struct {
uint8_t clsID; //Message Class [- -]
uint8_t msgID; //Message Identifier [- -]
uint8_t ck_a;
uint8_t ck_b;
} uBloxACKACKayload;
typedef struct {
uint8_t msgClass; //Message Class [- -]
uint8_t msgID; //Message Identifier [- -]
} uBloxCFGMSGPOLLPayload;
typedef struct {
uint8_t msgClass; //Message Class [- -]
uint8_t msgID; //Message Identifier [- -]
uint8_t rate; //Send rate on current Port [- -]
} uBloxCFGMSGPayload;
typedef struct {
uint16_t navBbrMask; //BBR Sections to clear. The following Special Sets apply:
// 0x0000 Hotstart
// 0x0001 Warmstart
// 0xFFFF Coldstart [- -]
uint8_t resetMode; //Reset Type
// - 0x00 - Hardware reset (Watchdog) immediately
// - 0x01 - Controlled Software reset
// - 0x02 - Controlled Software reset (GPS only)
// - 0x04 - Hardware reset (Watchdog) after shutdown (>=FW6.0)
// - 0x08 - Controlled GPS stop
// - 0x09 - Controlled GPS start [- -]
// - 0x09 - Controlled GPS start [- -]
uint8_t reserved1; //Reserved [- -]
} uBloxCFGRSTPayload;
typedef struct {
uint16_t mask; //Parameters Bitmask. Only the masked parameters will be applied. (see graphic below) [- -]
uint8_t dynModel; //Dynamic Platform model: - 0 􀀀 Portable - 2 􀀀 Stationary - 3 􀀀 Pedestrian - 4 􀀀 Automotive - 5 􀀀 Sea - 6 􀀀 Airborne with <1g Acceleration - 7 􀀀 Airborne with <2g Acceleration - 8 􀀀 Airborne with <4g Acceleration [- -]
uint8_t fixMode; //Position Fixing Mode. - 1: 2D only - 2: 3D only - 3: Auto 2D/3D [- -]
int32_t fixedAlt; //Fixed altitude (mean sea level) for 2D fix mode. [0.01 m]
uint32_t fixedAltVar; //Fixed altitude variance for 2D mode. [0.0001 m^2]
int8_t minElev; //Minimum Elevation for a GNSS satellite to be used in NAV [- deg]
uint8_t drLimit; //Maximum time to perform dead reckoning (linear extrapolation) in case of GPS signal loss [- s]
uint16_t pDop; //Position DOP Mask to use [0.1 -]
uint16_t tDop; //Time DOP Mask to use [0.1 -]
uint16_t pAcc; //Position Accuracy Mask [- m]
uint16_t tAcc; //Time Accuracy Mask [- m]
uint8_t staticHoldThresh; //Static hold threshold [- cm/s]
uint8_t dgpsTimeOut; //DGPS timeout, firmware 7 and newer only [- s]
uint32_t reserved2; //Always set to zero [- -]
uint32_t reserved3; //Always set to zero [- -]
uint32_t reserved4; //Always set to zero [- -]
} uBloxCFGNAV5Payload;
typedef struct {
uint8_t reserved1; //Always set to 8 [- -]
uint8_t lpMode; //Low Power Mode 0: Max. performance mode 1: Power Save Mode (>= FW 6.00 only) 2-3: reserved 4: Eco mode 5-255: reserved [- -]
} uBloxCFGRXMPayload;
typedef struct {
uint16_t measRate; //Measurement Rate, GPS measurements are taken every measRate milliseconds [- ms]
uint16_t navRate; //Navigation Rate, in number of measurement cycles. On u-blox 5 and u-blox 6, this parameter cannot be changed, and is always equals 1. [- cycles]
uint16_t timeRef; //Alignment to reference time: 0 = UTC time, 1 = GPS time [- -]
} uBloxCFGRATEPayload;
typedef union {
uBloxNAVPVTPayload navpvt;
uBloxCFGPRTPayload cfgprt;
uBloxCFGMSGPOLLPayload cfgmsgpoll;
uBloxCFGMSGPayload cfgmsg;
uBloxCFGNAV5Payload cfgnav5;
uBloxNAVPOSLLHPayload navposllh;
uBloxNAVSOLPayload navsol;
uBloxNAVTIMEGPSPayload navtimegps;
uBloxNAVTIMEUTCPayload navtimeutc;
uBloxNAVVELNEDPayload navvelned;
uBloxACKACKayload ackack;
uBloxCFGRSTPayload cfgrst;
uBloxCFGRXMPayload cfgrxm;
uBloxCFGRATEPayload cfgrate;
} ubloxPacketData;
typedef struct __attribute__((packed)) {
uBloxHeader header;
ubloxPacketData data;
} uBloxPacket;
gps_data current_gps_data;
volatile bool gps_initialized = false;
volatile bool ack_received = false;
volatile bool nack_received = false;
@ -35,17 +245,18 @@ ubxg6010_calculate_checksum(const uint8_t msgClass, const uint8_t msgId, const u
return ck;
}
static bool ubxg6010_wait_for_ack()
static void ubxg6010_clear_ack()
{
ack_received = false;
nack_received = false;
uint8_t timeout = 200;
}
while (!ack_received && !nack_received) {
static bool ubxg6010_wait_for_ack()
{
uint16_t timeout = 1500;
while (!ack_received && !nack_received && timeout-- > 0) {
delay_ms(1);
if (!timeout--) {
break;
}
}
return ack_received;
@ -53,6 +264,8 @@ static bool ubxg6010_wait_for_ack()
void ubxg6010_send_command(uint8_t msgClass, uint8_t msgId, uint8_t *payload, uint16_t payloadSize)
{
ubxg6010_clear_ack();
uBloxChecksum chksum = ubxg6010_calculate_checksum(msgClass, msgId, payload, payloadSize);
usart_gps_send_byte(0xB5);
@ -89,128 +302,221 @@ bool ubxg6010_send_packet_and_wait_for_ack(uBloxPacket *packet)
return success;
}
void ubxg6010_get_current_gps_data(gps_data *data)
bool ubxg6010_get_current_gps_data(gps_data *data)
{
system_disable_irq();
memcpy(data, &current_gps_data, sizeof(gps_data));
current_gps_data.updated = false;
system_enable_irq();
return data->updated;
}
uBloxPacket msgcfgrst = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x04,
.payloadSize=sizeof(uBloxCFGRSTPayload)
},
.data.cfgrst = {
.navBbrMask=0xffff, // Coldstart
.resetMode=1, // Controlled Software reset
.reserved1=0
},
};
uBloxPacket msgcfgprt = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x00,
.payloadSize=sizeof(uBloxCFGPRTPayload)
},
.data.cfgprt = {
.portID=1,
.reserved1=0,
.txReady=0,
.mode=0b0000100011000000, // 8 bits, no parity, 1 stop bit
.baudRate=38400,
.inProtoMask=1, // UBX protocol for input
.outProtoMask=1, // UBX protocol for output
.flags=0,
.reserved2={0, 0}
},
};
/**
* Low Power Mode
* 0: Max. performance mode
* 1: Power Save Mode (>= FW 6.00 only)
* 2-3: reserved
* 4: Eco mode
* 5-255: reserved
*/
uBloxPacket msgcfgrxm = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x11,
.payloadSize=sizeof(uBloxCFGRXMPayload)
},
.data.cfgrxm = {
.reserved1=8, // Always set to 8
.lpMode=0 // Low power mode: Eco mode -- TODO: set back to Eco mode
}
};
// Configure rate of 1 for message: 0x01 0x02 Geodetic Position Solution
uBloxPacket msgcfgmsg = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x01,
.payloadSize=sizeof(uBloxCFGMSGPayload)
},
.data.cfgmsg = {
.msgClass=0x01,
.msgID=0x02,
.rate=1
}
};
uBloxPacket msgcfgrate = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x08,
.payloadSize=sizeof(uBloxCFGRATEPayload)
},
.data.cfgrate = {
.measRate=1000,
.navRate=1,
.timeRef=0,
}
};
/**
* Dynamic Platform model:
* - 0 Portable
* - 2 Stationary
* - 3 Pedestrian
* - 4 Automotive
* - 5 Sea
* - 6 Airborne with <1g Acceleration
* - 7 Airborne with <2g Acceleration
* - 8 Airborne with <4g Acceleration
*
* Position Fixing Mode.
* - 1: 2D only
* - 2: 3D only
* - 3: Auto 2D/3D
*/
uBloxPacket msgcfgnav5 = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x24,
.payloadSize=sizeof(uBloxCFGNAV5Payload)
},
.data.cfgnav5={
.mask=0b0000001111111111, // Configure all settings
.dynModel=4, // Dynamic model: Airborne with <2g Acceleration -- TODO: 7
.fixMode=3, // Fix mode: 3D only -- TODO: 2
.fixedAlt=0, // Fixed altitude (mean sea level) for 2D fix mode.
.fixedAltVar=10000, // Fixed altitude variance for 2D mode.
.minElev=5, // Minimum Elevation for a GNSS satellite to be used in NAV (degrees)
.drLimit=0, // Maximum time to perform dead reckoning (linear extrapolation) in case of GPS signal loss (seconds)
.pDop=25, // Position DOP Mask to use
.tDop=25, // Time DOP Mask to use
.pAcc=100, // Position Accuracy Mask (m)
.tAcc=300, // Time Accuracy Mask (m)
.staticHoldThresh=0, // Static hold threshold (cm/s)
.dgpsTimeOut=2, // DGPS timeout, firmware 7 and newer only
.reserved2=0,
.reserved3=0,
.reserved4=0
},
};
bool ubxg6010_init()
{
bool success;
memset(&current_gps_data, 0, sizeof(gps_data));
gps_initialized = false;
log_info("GPS: Initializing USART with baud rate 38400\n");
usart_gps_init(38400, true);
delay_ms(10);
uBloxPacket msgcfgrst = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x04,
.payloadSize=sizeof(uBloxCFGRSTPayload)
},
.data.cfgrst = {
.navBbrMask=0xffff, // Coldstart
.resetMode=1, // Controlled Software reset
.reserved1=0
},
};
delay_ms(100);
log_info("GPS: Resetting GPS chip\n");
ubxg6010_send_packet(&msgcfgrst);
delay_ms(800);
delay_ms(1000);
log_info("GPS: Initializing USART with baud rate 9600\n");
usart_gps_init(9600, true);
delay_ms(10);
delay_ms(100);
log_info("GPS: Resetting GPS chip\n");
ubxg6010_send_packet(&msgcfgrst);
delay_ms(800);
delay_ms(1000);
uBloxPacket msgcfgprt = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x00,
.payloadSize=sizeof(uBloxCFGPRTPayload)
},
.data.cfgprt = {
.portID=1,
.reserved1=0,
.txReady=0,
.mode=0b0000100011000000, // 8 bits, no parity, 1 stop bit
.baudRate=38400,
.inProtoMask=1, // UBX protocol for input
.outProtoMask=1, // UBX protocol for output
.flags=0,
.reserved2={0, 0}
},
};
log_info("GPS: Configuring GPS chip serial port for baud rate 38400\n");
ubxg6010_send_packet(&msgcfgprt);
delay_ms(100);
log_info("GPS: Initializing USART with baud rate 38400\n");
usart_gps_init(38400, true);
delay_ms(10);
/**
* Low Power Mode
* 0: Max. performance mode
* 1: Power Save Mode (>= FW 6.00 only)
* 2-3: reserved
* 4: Eco mode
* 5-255: reserved
*/
uBloxPacket msgcfgrxm = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x11,
.payloadSize=sizeof(uBloxCFGRXMPayload)
},
.data.cfgrxm = {
.reserved1=8, // Always set to 8
.lpMode=0 // Low power mode: Eco mode -- TODO: set back to Eco mode
}
};
delay_ms(100);
log_info("GPS: Setting GPS chip power mode\n");
success = ubxg6010_send_packet_and_wait_for_ack(&msgcfgrxm);
if (!success) {
return false;
}
// Configure rate of 1 for message: 0x01 0x02 Geodetic Position Solution
uBloxPacket msgcfgmsg = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x01,
.payloadSize=sizeof(uBloxCFGMSGPayload)
},
.data.cfgmsg = {
.msgClass=0x01,
.msgID=0x02,
.rate=1
}
};
log_info("GPS: Requesting update messages from GPS chip\n");
success = ubxg6010_send_packet_and_wait_for_ack(&msgcfgmsg);
if (!success) {
return false;
}
log_info("GPS: Setting Navigation/Measurement rate settings in GPS chip\n");
success = ubxg6010_send_packet_and_wait_for_ack(&msgcfgrate);
if (!success) {
return false;
}
// Rate of 1 for message: 0x01 0x06 Navigation Solution Information
msgcfgmsg.data.cfgmsg.msgID = 0x6;
msgcfgmsg.data.cfgmsg.rate = 1;
log_info("GPS: Requesting update messages from GPS chip\n");
success = ubxg6010_send_packet_and_wait_for_ack(&msgcfgmsg);
if (!success) {
return false;
}
// Configure rate of 1 for message: 0x01 0x20 GPS Time Solution
/* msgcfgmsg.data.cfgmsg.msgID = 0x20;
msgcfgmsg.data.cfgmsg.rate = 1;
log_info("GPS: Requesting update messages from GPS chip\n");
success = ubxg6010_send_packet_and_wait_for_ack(&msgcfgmsg);
if (!success) {
return false;
}*/
// Configure rate of 1 for message: 0x01 0x21 UTC Time Solution
msgcfgmsg.data.cfgmsg.msgID = 0x21;
msgcfgmsg.data.cfgmsg.rate = 1;
log_info("GPS: Requesting update messages from GPS chip\n");
success = ubxg6010_send_packet_and_wait_for_ack(&msgcfgmsg);
if (!success) {
return false;
@ -219,6 +525,7 @@ bool ubxg6010_init()
// Configure rate of 2 for message: 0x01 0x12 Velocity Solution in NED
msgcfgmsg.data.cfgmsg.msgID = 0x12;
msgcfgmsg.data.cfgmsg.rate = 2;
log_info("GPS: Requesting update messages from GPS chip\n");
success = ubxg6010_send_packet_and_wait_for_ack(&msgcfgmsg);
if (!success) {
return false;
@ -231,58 +538,48 @@ bool ubxg6010_init()
return false;
}*/
/**
* Dynamic Platform model:
* - 0 Portable
* - 2 Stationary
* - 3 Pedestrian
* - 4 Automotive
* - 5 Sea
* - 6 Airborne with <1g Acceleration
* - 7 Airborne with <2g Acceleration
* - 8 Airborne with <4g Acceleration
*
* Position Fixing Mode.
* - 1: 2D only
* - 2: 3D only
* - 3: Auto 2D/3D
*/
uBloxPacket msgcfgnav5 = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x24,
.payloadSize=sizeof(uBloxCFGNAV5Payload)
},
.data.cfgnav5={
.mask=0b0000001111111111, // Configure all settings
.dynModel=7, // Dynamic model: Airborne with <2g Acceleration
.fixMode=2, // Fix mode: 3D only
.fixedAlt=0, // Fixed altitude (mean sea level) for 2D fix mode.
.fixedAltVar=10000, // Fixed altitude variance for 2D mode.
.minElev=5, // Minimum Elevation for a GNSS satellite to be used in NAV (degrees)
.drLimit=0, // Maximum time to perform dead reckoning (linear extrapolation) in case of GPS signal loss (seconds)
.pDop=25, // Position DOP Mask to use
.tDop=25, // Time DOP Mask to use
.pAcc=100, // Position Accuracy Mask (m)
.tAcc=300, // Time Accuracy Mask (m)
.staticHoldThresh=0, // Static hold threshold (cm/s)
.dgpsTimeOut=2, // DGPS timeout, firmware 7 and newer only
.reserved2=0,
.reserved3=0,
.reserved4=0
},
};
log_info("GPS: Configuring navigation engine settings\n");
success = ubxg6010_send_packet_and_wait_for_ack(&msgcfgnav5);
if (!success) {
return false;
}
gps_initialized = true;
return true;
}
// Poll request for message: 0x01 0x20 GPS Time Solution
uBloxPacket msgnavgpstime = {
.header = {
0xb5,
0x62,
.messageClass=0x01,
.messageId=0x20,
.payloadSize=0
}
};
uBloxPacket msgcfgmsgpoll = {
.header = {
0xb5,
0x62,
.messageClass=0x06,
.messageId=0x01,
.payloadSize=sizeof(uBloxCFGMSGPOLLPayload)
},
.data.cfgmsgpoll = {
.msgClass=0x01,
.msgID=0x20,
}
};
void ubxg6010_request_gpstime()
{
//ubxg6010_send_packet(&msgcfgmsgpoll);
ubxg6010_send_packet(&msgnavgpstime);
}
static void ubxg6010_handle_packet(uBloxPacket *pkt)
{
uBloxChecksum cksum = ubxg6010_calculate_checksum(pkt->header.messageClass, pkt->header.messageId,
@ -294,14 +591,10 @@ static void ubxg6010_handle_packet(uBloxPacket *pkt)
return;
}
if (pkt->header.messageClass == 0x01) {
log_info("class: %02X, id %02X\n", pkt->header.messageClass, pkt->header.messageId);
}
log_debug("GPS message: class=0x%02X id=0x%02X\n", pkt->header.messageClass, pkt->header.messageId);
if (pkt->header.messageClass == 0x01 && pkt->header.messageId == 0x07) {
// TODO: It seems NAV PVT message is not supported by UBXG6010, confirm this
log_info("class: %02X, id %02X, fix: %d\n", pkt->header.messageClass, pkt->header.messageId,
pkt->data.navpvt.fixType);
current_gps_data.ok_packets += 1;
current_gps_data.time_of_week_millis = pkt->data.navpvt.iTOW;
current_gps_data.year = pkt->data.navpvt.year;
@ -312,43 +605,52 @@ static void ubxg6010_handle_packet(uBloxPacket *pkt)
current_gps_data.seconds = pkt->data.navpvt.sec;
current_gps_data.fix = pkt->data.navpvt.fixType;
current_gps_data.lat_raw = pkt->data.navpvt.lat;
current_gps_data.lon_raw = pkt->data.navpvt.lon;
current_gps_data.alt_raw = pkt->data.navpvt.hMSL;
current_gps_data.sats_raw = pkt->data.navpvt.numSV;
current_gps_data.speed_raw = pkt->data.navpvt.gSpeed;
current_gps_data.heading_raw = pkt->data.navpvt.headMot;
current_gps_data.climb_raw = -pkt->data.navpvt.velD;
current_gps_data.latitude_degrees_1000000 = pkt->data.navpvt.lat;
current_gps_data.longitude_degrees_1000000 = pkt->data.navpvt.lon;
current_gps_data.altitude_mm = pkt->data.navpvt.hMSL;
current_gps_data.satellites_visible = pkt->data.navpvt.numSV;
current_gps_data.ground_speed_cm_per_second = pkt->data.navpvt.gSpeed;
current_gps_data.heading_degrees_100000 = pkt->data.navpvt.headMot;
current_gps_data.climb_cm_per_second = -pkt->data.navpvt.velD;
current_gps_data.updated = true;
} else if (pkt->header.messageClass == 0x01 && pkt->header.messageId == 0x12) {
log_info("class: %02X, id %02X\n", pkt->header.messageClass, pkt->header.messageId);
current_gps_data.ok_packets += 1;
current_gps_data.time_of_week_millis = pkt->data.navvelned.iTOW;
current_gps_data.speed_raw = pkt->data.navvelned.gSpeed;
current_gps_data.heading_raw = pkt->data.navvelned.headMot;
current_gps_data.climb_raw = -pkt->data.navvelned.velD;
current_gps_data.ground_speed_cm_per_second = pkt->data.navvelned.gSpeed;
current_gps_data.heading_degrees_100000 = pkt->data.navvelned.headMot;
current_gps_data.climb_cm_per_second = -pkt->data.navvelned.velD;
current_gps_data.updated = true;
} else if (pkt->header.messageClass == 0x01 && pkt->header.messageId == 0x02) {
log_info("class: %02X, id %02X\n", pkt->header.messageClass, pkt->header.messageId);
current_gps_data.ok_packets += 1;
current_gps_data.time_of_week_millis = pkt->data.navposllh.iTOW;
current_gps_data.lat_raw = pkt->data.navposllh.lat;
current_gps_data.lon_raw = pkt->data.navposllh.lon;
current_gps_data.alt_raw = pkt->data.navposllh.hMSL;
current_gps_data.latitude_degrees_1000000 = pkt->data.navposllh.lat;
current_gps_data.longitude_degrees_1000000 = pkt->data.navposllh.lon;
current_gps_data.altitude_mm = pkt->data.navposllh.hMSL;
current_gps_data.updated = true;
} else if (pkt->header.messageClass == 0x01 && pkt->header.messageId == 0x06) {
log_info("class: %02X, id %02X, flags: %02X, SV: %d, fix: %d\n", pkt->header.messageClass,
pkt->header.messageId,
pkt->data.navsol.flags, pkt->data.navsol.numSV, pkt->data.navsol.gpsFix);
current_gps_data.time_of_week_millis = pkt->data.navsol.iTOW;
current_gps_data.week = pkt->data.navsol.week;
current_gps_data.fix = pkt->data.navsol.gpsFix;
current_gps_data.sats_raw = pkt->data.navsol.numSV;
current_gps_data.satellites_visible = pkt->data.navsol.numSV;
current_gps_data.updated = true;
} else if (pkt->header.messageClass == 0x01 && pkt->header.messageId == 0x20) {
current_gps_data.time_of_week_millis = pkt->data.navtimegps.iTOW;
current_gps_data.week = pkt->data.navtimegps.week;
current_gps_data.updated = true;
} else if (pkt->header.messageClass == 0x01 && pkt->header.messageId == 0x21) {
log_info("class: %02X, id %02X\n", pkt->header.messageClass, pkt->header.messageId);
current_gps_data.year = pkt->data.navtimeutc.year;
current_gps_data.month = pkt->data.navtimeutc.month;
current_gps_data.day = pkt->data.navtimeutc.day;
current_gps_data.hours = pkt->data.navtimeutc.hour;
current_gps_data.minutes = pkt->data.navtimeutc.min;
current_gps_data.seconds = pkt->data.navtimeutc.sec;
current_gps_data.updated = true;
} else if (pkt->header.messageClass == 0x05 && pkt->header.messageId == 0x01) {
ack_received = true;
} else if (pkt->header.messageClass == 0x05 && pkt->header.messageId == 0x00) {

Wyświetl plik

@ -5,198 +5,11 @@
#include "src/gps.h"
typedef struct __attribute__((packed)) {
uint8_t sc1; // 0xB5
uint8_t sc2; // 0x62
uint8_t messageClass;
uint8_t messageId;
uint16_t payloadSize;
} uBloxHeader;
typedef struct {
uint8_t ck_a;
uint8_t ck_b;
} uBloxChecksum;
typedef struct {
uint32_t iTOW; //GPS time of week of the navigation epoch. [- ms]
uint16_t year; //Year (UTC) [- y]
uint8_t month; //Month, range 1..12 (UTC) [- month]
uint8_t day; //Day of month, range 1..31 (UTC) [- d]
uint8_t hour; //Hour of day, range 0..23 (UTC) [- h]
uint8_t min; //Minute of hour, range 0..59 (UTC) [- min]
uint8_t sec; //Seconds of minute, range 0..60 (UTC) [- s]
uint8_t valid; //Validity flags (see graphic below) [- -]
uint32_t tAcc; //Time accuracy estimate (UTC) [- ns]
int32_t nano; //Fraction of second, range -1e9 .. 1e9 (UTC) [- ns]
uint8_t fixType; //GNSSfix Type: [- -]
uint8_t flags; //Fix status flags (see graphic below) [- -]
uint8_t flags2; //Additional flags (see graphic below) [- -]
uint8_t numSV; //Number of satellites used in Nav Solution [- -]
int32_t lon; //Longitude [1e-7 deg]
int32_t lat; //Latitude [1e-7 deg]
int32_t height; //Height above ellipsoid [- mm]
int32_t hMSL; //Height above mean sea level [- mm]
uint32_t hAcc; //Horizontal accuracy estimate [- mm]
uint32_t vAcc; //Vertical accuracy estimate [- mm]
int32_t velN; //NED north velocity [- mm/s]
int32_t velE; //NED east velocity [- mm/s]
int32_t velD; //NED down velocity [- mm/s]
int32_t gSpeed; //Ground Speed (2-D) [- mm/s]
int32_t headMot; //Heading of motion (2-D) [1e-5 deg]
uint32_t sAcc; //Speed accuracy estimate [- mm/s]
uint32_t headAcc; //Heading accuracy estimate (both motion and vehicle) [1e-5 deg]
uint16_t pDOP; //Position DOP [0.01 -]
uint8_t reserved1[6]; //Reserved [- -]
int32_t headVeh; //Heading of vehicle (2-D) [1e-5 deg]
uint8_t reserved2[4]; //Reserved [- -]
} uBloxNAVPVTPayload;
typedef struct {
uint32_t iTOW; //GPS Millisecond Time of Week [- ms]
int32_t lon; //Longitude [1e-7 deg]
int32_t lat; //Latitude [1e-7 deg]
int32_t height; //Height above Ellipsoid [- mm]
int32_t hMSL; //Height above mean sea level [- mm]
uint32_t hAcc; //Horizontal Accuracy Estimate [- mm]
uint32_t vAcc; //Vertical Accuracy Estimate [- mm]
} uBloxNAVPOSLLHPayload;
typedef struct {
uint32_t iTOW; //GPS Millisecond Time of Week [- ms]
int32_t fTOW; //Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000 [- ns]
int16_t week; //GPS week (GPS time) [- -]
uint8_t gpsFix; //GPSfix Type, range 0..5 0x00 = No Fix 0x01 = Dead Reckoning only 0x02 = 2D-Fix 0x03 = 3D-Fix 0x04 = GPS + dead reckoning combined 0x05 = Time only fix 0x06..0xff: reserved [- -]
uint8_t flags; //Fix Status Flags (see graphic below) [- -]
int32_t ecefX; //ECEF X coordinate [- cm]
int32_t ecefY; //ECEF Y coordinate [- cm]
int32_t ecefZ; //ECEF Z coordinate [- cm]
uint32_t pAcc; //3D Position Accuracy Estimate [- cm]
int32_t ecefVX; //ECEF X velocity [- cm/s]
int32_t ecefVY; //ECEF Y velocity [- cm/s]
int32_t ecefVZ; //ECEF Z velocity [- cm/s]
uint32_t sAcc; //Speed Accuracy Estimate [- cm/s]
uint16_t pDOP; //Position DOP [0.01 -]
uint8_t reserved1; //Reserved [- -]
uint8_t numSV; //Number of SVs used in Nav Solution [- -]
uint32_t reserved2; //Reserved [- -]
} uBloxNAVSOLPayload;
typedef struct {
uint32_t iTOW; //GPS Millisecond Time of Week [- ms]
uint32_t tAcc; //Time Accuracy Estimate [- ns]
int32_t nano; //Nanoseconds of second, range -1e9 .. 1e9 (UTC) [- ns]
uint16_t year; //Year, range 1999..2099 (UTC) [- y]
uint8_t month; //Month, range 1..12 (UTC) [- month]
uint8_t day; //Day of Month, range 1..31 (UTC) [- d]
uint8_t hour; //Hour of Day, range 0..23 (UTC) [- h]
uint8_t min; //Minute of Hour, range 0..59 (UTC) [- min]
uint8_t sec; //Seconds of Minute, range 0..59 (UTC) [- s]
uint8_t valid; //Validity Flags (see graphic below) [- -]
} uBloxNAVTIMEUTCPayload;
typedef struct {
uint32_t iTOW; //GPS Millisecond Time of Week [- ms]
int32_t velN; //NED north velocity [- cm/s]
int32_t velE; //NED east velocity [- cm/s]
int32_t velD; //NED down velocity [- cm/s]
uint32_t speed; //Speed (3-D) [- cm/s]
uint32_t gSpeed; //Ground Speed (2-D) [- cm/s]
int32_t headMot; //Heading of motion (2-D) [1e-5 deg]
uint32_t sAcc; //Speed accuracy estimate [- cm/s]
uint32_t headAcc; //Heading accuracy estimate (both motion and vehicle) [1e-5 deg]
} uBloxNAVVELNEDPayload;
typedef struct {
uint8_t portID; //Port Identifier Number (see Serial [- -]
uint8_t reserved1; //Reserved [- -]
uint16_t txReady; //TX ready PIN configuration [- -]
uint32_t mode; //A bit mask describing the UART mode [- -]
uint32_t baudRate; //Baud rate in bits/second [- Bits/s]
uint16_t inProtoMask; //A mask describing which input protocols are active. [- -]
uint16_t outProtoMask; //A mask describing which output protocols are active. [- -]
uint16_t flags; //Flags bit mask (see graphic below) [- -]
uint8_t reserved2[2]; //Reserved [- -]
} uBloxCFGPRTPayload;
typedef struct {
uint8_t clsID; //Message Class [- -]
uint8_t msgID; //Message Identifier [- -]
uint8_t ck_a;
uint8_t ck_b;
} uBloxACKACKayload;
typedef struct {
uint8_t msgClass; //Message Class [- -]
uint8_t msgID; //Message Identifier [- -]
uint8_t rate; //Send rate on current Port [- -]
} uBloxCFGMSGPayload;
typedef struct {
uint16_t navBbrMask; //BBR Sections to clear. The following Special Sets apply:
// 0x0000 Hotstart
// 0x0001 Warmstart
// 0xFFFF Coldstart [- -]
uint8_t resetMode; //Reset Type
// - 0x00 - Hardware reset (Watchdog) immediately
// - 0x01 - Controlled Software reset
// - 0x02 - Controlled Software reset (GPS only)
// - 0x04 - Hardware reset (Watchdog) after shutdown (>=FW6.0)
// - 0x08 - Controlled GPS stop
// - 0x09 - Controlled GPS start [- -]
// - 0x09 - Controlled GPS start [- -]
uint8_t reserved1; //Reserved [- -]
} uBloxCFGRSTPayload;
typedef struct {
uint16_t mask; //Parameters Bitmask. Only the masked parameters will be applied. (see graphic below) [- -]
uint8_t dynModel; //Dynamic Platform model: - 0 􀀀 Portable - 2 􀀀 Stationary - 3 􀀀 Pedestrian - 4 􀀀 Automotive - 5 􀀀 Sea - 6 􀀀 Airborne with <1g Acceleration - 7 􀀀 Airborne with <2g Acceleration - 8 􀀀 Airborne with <4g Acceleration [- -]
uint8_t fixMode; //Position Fixing Mode. - 1: 2D only - 2: 3D only - 3: Auto 2D/3D [- -]
int32_t fixedAlt; //Fixed altitude (mean sea level) for 2D fix mode. [0.01 m]
uint32_t fixedAltVar; //Fixed altitude variance for 2D mode. [0.0001 m^2]
int8_t minElev; //Minimum Elevation for a GNSS satellite to be used in NAV [- deg]
uint8_t drLimit; //Maximum time to perform dead reckoning (linear extrapolation) in case of GPS signal loss [- s]
uint16_t pDop; //Position DOP Mask to use [0.1 -]
uint16_t tDop; //Time DOP Mask to use [0.1 -]
uint16_t pAcc; //Position Accuracy Mask [- m]
uint16_t tAcc; //Time Accuracy Mask [- m]
uint8_t staticHoldThresh; //Static hold threshold [- cm/s]
uint8_t dgpsTimeOut; //DGPS timeout, firmware 7 and newer only [- s]
uint32_t reserved2; //Always set to zero [- -]
uint32_t reserved3; //Always set to zero [- -]
uint32_t reserved4; //Always set to zero [- -]
} uBloxCFGNAV5Payload;
typedef struct {
uint8_t reserved1; //Always set to 8 [- -]
uint8_t lpMode; //Low Power Mode 0: Max. performance mode 1: Power Save Mode (>= FW 6.00 only) 2-3: reserved 4: Eco mode 5-255: reserved [- -]
} uBloxCFGRXMPayload;
typedef union {
uBloxNAVPVTPayload navpvt;
uBloxCFGPRTPayload cfgprt;
uBloxCFGMSGPayload cfgmsg;
uBloxCFGNAV5Payload cfgnav5;
uBloxNAVPOSLLHPayload navposllh;
uBloxNAVSOLPayload navsol;
uBloxNAVTIMEUTCPayload navtimeutc;
uBloxNAVVELNEDPayload navvelned;
uBloxACKACKayload ackack;
uBloxCFGRSTPayload cfgrst;
uBloxCFGRXMPayload cfgrxm;
} ubloxPacketData;
typedef struct __attribute__((packed)) {
uBloxHeader header;
ubloxPacketData data;
} uBloxPacket;
bool ubxg6010_init();
void ubxg6010_get_current_gps_data(gps_data *data);
void ubxg6010_request_gpstime();
bool ubxg6010_get_current_gps_data(gps_data *data);
void ubxg6010_handle_incoming_byte(uint8_t data);

Wyświetl plik

@ -2,8 +2,11 @@
#define __GPS_H
#include <stdint.h>
#include <stdbool.h>
typedef struct _gps_data {
bool updated;
uint32_t time_of_week_millis;
int16_t week;
uint16_t year;
@ -13,13 +16,13 @@ typedef struct _gps_data {
uint8_t minutes;
uint8_t hours;
int32_t lat_raw;
int32_t lon_raw;
int32_t alt_raw;
int32_t speed_raw;
int32_t heading_raw;
int32_t climb_raw;
uint8_t sats_raw;
int32_t latitude_degrees_1000000;
int32_t longitude_degrees_1000000;
int32_t altitude_mm;
uint32_t ground_speed_cm_per_second;
int32_t heading_degrees_100000;
int32_t climb_cm_per_second;
uint8_t satellites_visible;
uint8_t fix;
uint16_t ok_packets;
uint16_t bad_packets;

Wyświetl plik

@ -294,10 +294,6 @@ uint32_t system_get_tick()
return systick_counter;
}
// TODO: create RTTY / FSK encoder for Si5351
// TODO: create RTTY / FSK encoder for Si4032
// TODO: create CW / OOK encoder -- the same one should work for both Si5351 and Si4032
void SysTick_Handler()
{
systick_counter++;

Wyświetl plik

@ -3,12 +3,12 @@
#include "config.h"
#ifdef SEMIHOSTING_ENABLE
#if defined(SEMIHOSTING_ENABLE) && defined(LOGGING_ENABLE)
#include <stdio.h>
#define log_error(...)
#define log_warn(...)
#define log_error printf
#define log_warn printf
#define log_info printf
#define log_debug(...)
#define log_trace(...)

Wyświetl plik

@ -1,3 +1,4 @@
#include <stdio.h>
#include "hal/system.h"
#include "hal/i2c.h"
#include "hal/spi.h"
@ -64,7 +65,8 @@ gps_init:
log_info("GPS init\n");
success = ubxg6010_init();
if (!success) {
log_error("GPS initialization failed, retrying...\n")
log_error("GPS initialization failed, retrying...\n");
delay_ms(1000);
goto gps_init;
}

Wyświetl plik

@ -1,173 +1,43 @@
#include <stdio.h>
#include "config.h"
#include "payload.h"
#include "telemetry.h"
#include "log.h"
#include "hal/system.h"
#include "hal/delay.h"
#include "hal/spi.h"
#include "hal/pwm.h"
#include "hal/usart_gps.h"
#include "codecs/fsk/fsk.h"
#include "codecs/bell/bell.h"
#include "codecs/aprs/aprs.h"
#include "codecs/ax25/ax25.h"
#include "codecs/jtencode/jtencode.h"
#include "drivers/si4032/si4032.h"
#include "si5351_handler.h"
#include "drivers/ubxg6010/ubxg6010.h"
#include "radio_internal.h"
#include "radio_si4032.h"
#include "radio_si5351.h"
#include "radio_payload_aprs.h"
#include "radio_payload_wspr.h"
#include "radio_payload_ft8.h"
typedef enum _radio_type {
RADIO_TYPE_SI4032 = 1,
RADIO_TYPE_SI5351,
} radio_type;
// TODO: create RTTY / FSK encoder for Si5351
// TODO: create RTTY / FSK encoder for Si4032
// TODO: create CW / OOK encoder -- the same one should work for both Si5351 and Si4032
typedef enum _radio_data_mode {
RADIO_DATA_MODE_CW = 1,
RADIO_DATA_MODE_RTTY,
RADIO_DATA_MODE_APRS,
RADIO_DATA_MODE_WSPR,
RADIO_DATA_MODE_FT8,
RADIO_DATA_MODE_JT65,
RADIO_DATA_MODE_JT4,
RADIO_DATA_MODE_JT9,
RADIO_DATA_MODE_FSQ_2,
RADIO_DATA_MODE_FSQ_3,
RADIO_DATA_MODE_FSQ_4_5,
RADIO_DATA_MODE_FSQ_6,
} radio_data_mode;
typedef struct _radio_transmit_entry {
radio_type radio_type;
radio_data_mode data_mode;
uint32_t frequency;
uint8_t tx_power;
uint32_t symbol_rate;
payload_encoder *payload_encoder;
fsk_encoder_api *fsk_encoder_api;
jtencode_mode_type jtencode_mode_type;
fsk_encoder fsk_encoder;
} radio_transmit_entry;
#ifdef SEMIHOSTING_ENABLE
char logged_payload[512];
#endif
static bool si4032_use_dma = false;
static radio_transmit_entry *radio_current_transmit_entry = NULL;
static uint8_t radio_current_transmit_entry_index = 0;
static volatile bool radio_transmission_active = false;
static volatile bool radio_transmission_finished = false;
static volatile uint32_t radio_post_transmit_delay_counter = 0;
static volatile uint32_t radio_next_symbol_counter = 0;
static volatile bool radio_si5351_state_change = false;
static volatile uint64_t radio_si5351_freq = 0;
static volatile bool radio_si4032_state_change = false;
static volatile uint32_t radio_si4032_freq = 0;
static radio_transmit_entry *radio_start_transmit_entry = NULL;
static radio_transmit_entry *radio_stop_transmit_entry = NULL;
static volatile bool radio_transmit_next_symbol_flag = false;
static volatile uint32_t radio_symbol_count_interrupt = 0;
static volatile uint32_t radio_symbol_count_loop = 0;
static volatile bool radio_dma_transfer_active = false;
static volatile int8_t radio_dma_transfer_stop_after_counter = -1;
static volatile bool radio_manual_transmit_active = false;
uint8_t radio_current_payload[RADIO_PAYLOAD_MAX_LENGTH];
uint16_t radio_current_payload_length = 0;
fsk_tone *radio_current_fsk_tones = NULL;
int8_t radio_current_fsk_tone_count = 0;
uint32_t radio_current_tone_spacing_hz_100 = 0;
uint32_t radio_current_symbol_rate = 0;
uint32_t radio_current_symbol_delay_ms_100 = 0;
telemetry_data current_telemetry_data;
uint8_t aprs_packet[RADIO_PAYLOAD_MAX_LENGTH];
char aprs_comment[APRS_COMMENT_MAX_LENGTH];
static volatile uint32_t start_tick = 0, end_tick = 0;
static uint16_t radio_fill_pwm_buffer(uint16_t offset, uint16_t length, uint16_t *buffer);
uint16_t radio_aprs_encode(uint8_t *payload, uint16_t length, telemetry_data *telemetry_data)
{
gps_data *gps = &telemetry_data->gps;
snprintf(aprs_comment, sizeof(aprs_comment), " RS41ng test, time is %02d:%02d:%02d, locator %s, TOW %lu ms, gs %lu, hd %ld",
gps->hours, gps->minutes, gps->seconds, telemetry_data->locator, gps->time_of_week_millis,
gps->speed_raw, gps->heading_raw);
aprs_generate_position_without_timestamp(
aprs_packet, sizeof(aprs_packet), telemetry_data, APRS_SYMBOL_TABLE, APRS_SYMBOL, aprs_comment);
log_debug("APRS packet: %s\n", aprs_packet);
return ax25_encode_packet_aprs(APRS_CALLSIGN, APRS_SSID, APRS_DESTINATION, APRS_DESTINATION_SSID, APRS_RELAYS,
(char *) aprs_packet, length, payload);
}
payload_encoder radio_aprs_payload_encoder = {
.encode = radio_aprs_encode,
};
uint16_t radio_ft8_encode(uint8_t *payload, uint16_t length, telemetry_data *telemetry_data)
{
char locator[5];
#ifdef FT8_LOCATOR_FIXED
locator = FT8_LOCATOR_FIXED;
#else
strlcpy(locator, telemetry_data->locator, 4);
#endif
return snprintf((char *) payload, length, "%s %s", FT8_CALLSIGN, locator);
}
payload_encoder radio_ft8_payload_encoder = {
.encode = radio_ft8_encode,
};
uint16_t radio_wspr_encode(uint8_t *payload, uint16_t length, telemetry_data *telemetry_data)
{
// Not used for WSPR
return 0;
}
payload_encoder radio_wspr_payload_encoder = {
.encode = radio_wspr_encode,
};
#define RADIO_TRANSMIT_ENTRY_COUNT 1
static radio_transmit_entry radio_transmit_schedule[] = {
radio_transmit_entry radio_transmit_schedule[] = {
{
.enabled = true,
.radio_type = RADIO_TYPE_SI4032,
.data_mode = RADIO_DATA_MODE_APRS,
.time_sync_seconds = 0,
.time_sync_seconds_offset = 0,
.frequency = RADIO_SI4032_TX_FREQUENCY_APRS,
.tx_power = RADIO_SI4032_TX_POWER,
.symbol_rate = 1200,
.payload_encoder = &radio_aprs_payload_encoder,
.fsk_encoder_api = &bell_fsk_encoder_api,
},
/* {
{
.enabled = true,
.radio_type = RADIO_TYPE_SI5351,
.data_mode = RADIO_DATA_MODE_FT8,
.time_sync_seconds = 5,
.time_sync_seconds_offset = 0,
.frequency = RADIO_SI5351_TX_FREQUENCY_FT8,
.tx_power = RADIO_SI5351_TX_POWER,
.payload_encoder = &radio_ft8_payload_encoder,
@ -175,94 +45,70 @@ static radio_transmit_entry radio_transmit_schedule[] = {
.jtencode_mode_type = JTENCODE_MODE_FT8,
},
{
.enabled = false,
.radio_type = RADIO_TYPE_SI5351,
.time_sync_seconds = 300,
.time_sync_seconds_offset = 0,
.data_mode = RADIO_DATA_MODE_WSPR,
.frequency = RADIO_SI5351_TX_FREQUENCY_WSPR,
.tx_power = RADIO_SI5351_TX_POWER,
.payload_encoder = &radio_wspr_payload_encoder,
.fsk_encoder_api = &jtencode_fsk_encoder_api,
.jtencode_mode_type = JTENCODE_MODE_WSPR,
},*/
},
{
.end = true,
}
};
static bool radio_start_transmit_si4032(radio_transmit_entry *entry)
{
uint16_t frequency_offset;
si4032_modulation_type modulation_type;
bool use_direct_mode;
static volatile bool radio_module_initialized = false;
switch (entry->data_mode) {
case RADIO_DATA_MODE_CW:
frequency_offset = 1;
modulation_type = SI4032_MODULATION_TYPE_OOK;
use_direct_mode = true;
break;
case RADIO_DATA_MODE_RTTY:
frequency_offset = 0;
modulation_type = SI4032_MODULATION_TYPE_NONE;
use_direct_mode = false;
break;
case RADIO_DATA_MODE_APRS:
frequency_offset = 0;
modulation_type = SI4032_MODULATION_TYPE_FSK;
use_direct_mode = true;
if (si4032_use_dma) {
radio_fill_pwm_buffer(0, PWM_TIMER_DMA_BUFFER_SIZE, pwm_timer_dma_buffer);
}
break;
default:
return false;
}
const bool wspr_locator_fixed_enabled = WSPR_LOCATOR_FIXED_ENABLED;
si4032_set_tx_frequency(((float) entry->frequency) / 1000000.0f);
si4032_set_tx_power(entry->tx_power * 7 / 100);
si4032_set_frequency_offset(frequency_offset);
si4032_set_modulation_type(modulation_type);
radio_transmit_entry *radio_current_transmit_entry = NULL;
static uint8_t radio_current_transmit_entry_index = 0;
static uint8_t radio_transmit_entry_count = 0;
si4032_enable_tx();
static volatile uint32_t radio_post_transmit_delay_counter = 0;
static volatile uint32_t radio_next_symbol_counter = 0;
if (use_direct_mode) {
//delay_us(100);
spi_uninit();
pwm_timer_use(true);
pwm_timer_pwm_enable(true);
si4032_use_direct_mode(true);
}
static radio_transmit_entry *radio_start_transmit_entry = NULL;
switch (entry->data_mode) {
case RADIO_DATA_MODE_APRS:
if (si4032_use_dma) {
radio_dma_transfer_active = true;
radio_dma_transfer_stop_after_counter = -1;
system_disable_tick();
pwm_dma_start();
} else {
log_info("Si4032 manual TX\n");
radio_manual_transmit_active = true;
}
break;
default:
break;
}
static uint32_t radio_previous_time_sync_scheduled = 0;
return true;
}
uint8_t radio_current_payload[RADIO_PAYLOAD_MAX_LENGTH];
uint16_t radio_current_payload_length = 0;
static bool radio_start_transmit_si5351(radio_transmit_entry *entry)
{
si5351_set_drive_strength(SI5351_CLOCK_CLK0, entry->tx_power * 3 / 100);
si5351_set_frequency(SI5351_CLOCK_CLK0, ((uint64_t) entry->frequency) * 100ULL);
si5351_output_enable(SI5351_CLOCK_CLK0, true);
return true;
}
uint8_t radio_current_symbol_data[RADIO_SYMBOL_DATA_MAX_LENGTH];
static volatile uint32_t start_tick = 0, end_tick = 0;
telemetry_data current_telemetry_data;
radio_module_state radio_shared_state = {
.radio_transmission_active = false,
.radio_transmission_finished = false,
.radio_transmit_next_symbol_flag = false,
.radio_symbol_count_interrupt = 0,
.radio_symbol_count_loop = 0,
.radio_dma_transfer_active = false,
.radio_manual_transmit_active = false,
.radio_current_fsk_tones = NULL,
.radio_current_fsk_tone_count = 0,
.radio_current_tone_spacing_hz_100 = 0,
.radio_current_symbol_rate = 0,
.radio_current_symbol_delay_ms_100 = 0
};
static inline void radio_reset_next_symbol_counter()
{
if (radio_current_symbol_rate > 0) {
if (radio_shared_state.radio_current_symbol_rate > 0) {
radio_next_symbol_counter = (uint32_t) (((float) SYSTEM_SCHEDULER_TIMER_TICKS_PER_SECOND) /
(float) radio_current_symbol_rate);
(float) radio_shared_state.radio_current_symbol_rate);
} else {
radio_next_symbol_counter = (uint32_t) (((float) radio_current_symbol_delay_ms_100) *
radio_next_symbol_counter = (uint32_t) (((float) radio_shared_state.radio_current_symbol_delay_ms_100) *
(float) SYSTEM_SCHEDULER_TIMER_TICKS_PER_SECOND / 100000.0f);
}
}
@ -276,8 +122,8 @@ static bool radio_start_transmit(radio_transmit_entry *entry)
{
bool success;
radio_symbol_count_interrupt = 0;
radio_symbol_count_loop = 0;
radio_shared_state.radio_symbol_count_interrupt = 0;
radio_shared_state.radio_symbol_count_loop = 0;
telemetry_collect(&current_telemetry_data);
@ -287,18 +133,16 @@ static bool radio_start_transmit(radio_transmit_entry *entry)
log_info("Full payload length: %d\n", radio_current_payload_length);
#ifdef SEMIHOSTING_ENABLE
int16_t len = 0;
log_info("Payload: ");
for (uint16_t i = 0; i < radio_current_payload_length; i++) {
char c = radio_current_payload[i];
if (c >= 0x20 && c <= 0x7e) {
len += sprintf(logged_payload + len, "%c", c);
log_info("%c", c);
} else {
len += sprintf(logged_payload + len, " [%02X] ", c);
log_info(" [%02X] ", c);
}
}
log_info("%s\n", logged_payload);
log_info("\n");
#endif
switch (entry->data_mode) {
@ -309,9 +153,9 @@ static bool radio_start_transmit(radio_transmit_entry *entry)
case RADIO_DATA_MODE_APRS:
// TODO: make bell tones and flag field count configurable
bell_encoder_new(&entry->fsk_encoder, entry->symbol_rate, BELL_FLAG_FIELD_COUNT_1200, bell202_tones);
radio_current_symbol_rate = entry->fsk_encoder_api->get_symbol_rate(&entry->fsk_encoder);
entry->fsk_encoder_api->get_tones(&entry->fsk_encoder, &radio_current_fsk_tone_count,
&radio_current_fsk_tones);
radio_shared_state.radio_current_symbol_rate = entry->fsk_encoder_api->get_symbol_rate(&entry->fsk_encoder);
entry->fsk_encoder_api->get_tones(&entry->fsk_encoder, &radio_shared_state.radio_current_fsk_tone_count,
&radio_shared_state.radio_current_fsk_tones);
entry->fsk_encoder_api->set_data(&entry->fsk_encoder, radio_current_payload_length, radio_current_payload);
break;
case RADIO_DATA_MODE_WSPR:
@ -324,15 +168,23 @@ static bool radio_start_transmit(radio_transmit_entry *entry)
case RADIO_DATA_MODE_FSQ_4_5:
case RADIO_DATA_MODE_FSQ_6: {
char locator[5];
#ifdef WSPR_LOCATOR_FIXED
locator = WSPR_LOCATOR_FIXED;
#else
strlcpy(locator, current_telemetry_data.locator, 4);
#endif
jtencode_encoder_new(&entry->fsk_encoder, entry->jtencode_mode_type, WSPR_CALLSIGN, locator,
if (wspr_locator_fixed_enabled) {
strlcpy(locator, WSPR_LOCATOR_FIXED, 4 + 1);
} else {
strlcpy(locator, current_telemetry_data.locator, 4 + 1);
}
success = jtencode_encoder_new(&entry->fsk_encoder, sizeof(radio_current_symbol_data), radio_current_symbol_data,
entry->jtencode_mode_type, WSPR_CALLSIGN, locator,
WSPR_DBM, FSQ_CALLSIGN_FROM, FSQ_CALLSIGN_TO, FSQ_COMMAND);
radio_current_symbol_delay_ms_100 = entry->fsk_encoder_api->get_symbol_delay(&entry->fsk_encoder);
radio_current_tone_spacing_hz_100 = entry->fsk_encoder_api->get_tone_spacing(&entry->fsk_encoder);
if (!success) {
return false;
}
radio_shared_state.radio_current_symbol_delay_ms_100 = entry->fsk_encoder_api->get_symbol_delay(
&entry->fsk_encoder);
radio_shared_state.radio_current_tone_spacing_hz_100 = entry->fsk_encoder_api->get_tone_spacing(
&entry->fsk_encoder);
entry->fsk_encoder_api->set_data(&entry->fsk_encoder, radio_current_payload_length, radio_current_payload);
break;
}
@ -345,10 +197,10 @@ static bool radio_start_transmit(radio_transmit_entry *entry)
switch (entry->radio_type) {
case RADIO_TYPE_SI4032:
success = radio_start_transmit_si4032(entry);
success = radio_start_transmit_si4032(entry, &radio_shared_state);
break;
case RADIO_TYPE_SI5351:
success = radio_start_transmit_si5351(entry);
success = radio_start_transmit_si5351(entry, &radio_shared_state);
break;
default:
return false;
@ -360,80 +212,28 @@ static bool radio_start_transmit(radio_transmit_entry *entry)
return false;
}
log_info("TX enabled\n");
log_info("TX start\n");
system_set_red_led(true);
radio_transmission_active = true;
radio_shared_state.radio_transmission_active = true;
return true;
}
static bool radio_stop_transmit_si4032(radio_transmit_entry *entry)
{
bool use_direct_mode = false;
switch (entry->data_mode) {
case RADIO_DATA_MODE_CW:
use_direct_mode = true;
break;
case RADIO_DATA_MODE_RTTY:
use_direct_mode = false;
break;
case RADIO_DATA_MODE_APRS:
use_direct_mode = true;
if (si4032_use_dma) {
system_enable_tick();
}
break;
default:
break;
}
if (use_direct_mode) {
si4032_use_direct_mode(false);
pwm_timer_pwm_enable(false);
//delay_us(100);
pwm_timer_use(false);
//delay_us(100);
spi_init();
//delay_us(100);
}
si4032_inhibit_tx();
switch (entry->data_mode) {
case RADIO_DATA_MODE_APRS:
if (si4032_use_dma) {
system_enable_tick();
}
break;
default:
break;
}
return true;
}
static bool radio_stop_transmit_si5351(radio_transmit_entry *entry)
{
si5351_output_enable(SI5351_CLOCK_CLK0, false);
return true;
}
static inline void radio_reset_transmit_state()
{
radio_transmission_active = false;
radio_next_symbol_counter = 0;
radio_shared_state.radio_transmission_active = false;
radio_next_symbol_counter = 0;
radio_current_payload_length = 0;
radio_current_fsk_tones = NULL;
radio_current_fsk_tone_count = 0;
radio_current_tone_spacing_hz_100 = 0;
radio_shared_state.radio_current_fsk_tones = NULL;
radio_shared_state.radio_current_fsk_tone_count = 0;
radio_shared_state.radio_current_tone_spacing_hz_100 = 0;
radio_current_symbol_rate = 0;
radio_current_symbol_delay_ms_100 = 0;
radio_shared_state.radio_current_symbol_rate = 0;
radio_shared_state.radio_current_symbol_delay_ms_100 = 0;
}
static bool radio_stop_transmit(radio_transmit_entry *entry)
@ -442,10 +242,10 @@ static bool radio_stop_transmit(radio_transmit_entry *entry)
switch (entry->radio_type) {
case RADIO_TYPE_SI4032:
success = radio_stop_transmit_si4032(entry);
success = radio_stop_transmit_si4032(entry, &radio_shared_state);
break;
case RADIO_TYPE_SI5351:
success = radio_stop_transmit_si5351(entry);
success = radio_stop_transmit_si5351(entry, &radio_shared_state);
break;
default:
return false;
@ -453,8 +253,8 @@ static bool radio_stop_transmit(radio_transmit_entry *entry)
radio_reset_transmit_state();
radio_manual_transmit_active = false;
radio_dma_transfer_active = false;
radio_shared_state.radio_manual_transmit_active = false;
radio_shared_state.radio_dma_transfer_active = false;
switch (entry->data_mode) {
case RADIO_DATA_MODE_CW:
@ -485,121 +285,143 @@ static bool radio_stop_transmit(radio_transmit_entry *entry)
return success;
}
static uint32_t radio_next_symbol_si4032(radio_transmit_entry *entry)
{
switch (entry->data_mode) {
case RADIO_DATA_MODE_CW:
return 0;
case RADIO_DATA_MODE_RTTY:
return 0;
case RADIO_DATA_MODE_APRS: {
int8_t next_tone_index = entry->fsk_encoder_api->next_tone(&entry->fsk_encoder);
if (next_tone_index < 0) {
return 0;
}
return radio_current_fsk_tones[next_tone_index].frequency_hz_100;
}
default:
return 0;
}
}
static bool radio_transmit_symbol_si4032(radio_transmit_entry *entry)
{
uint32_t frequency = radio_next_symbol_si4032(entry);
if (frequency == 0) {
return false;
}
radio_si4032_freq = frequency;
radio_si4032_state_change = true;
return true;
}
static bool radio_transmit_symbol_si5351(radio_transmit_entry *entry)
{
switch (entry->data_mode) {
case RADIO_DATA_MODE_CW:
return false;
default: {
int8_t next_tone_index = entry->fsk_encoder_api->next_tone(&entry->fsk_encoder);
if (next_tone_index < 0) {
return false;
}
log_trace("Tone: %d\n", next_tone_index);
uint64_t frequency =
((uint64_t) entry->frequency) * 100UL + (next_tone_index * radio_current_tone_spacing_hz_100);
radio_si5351_freq = frequency;
radio_si5351_state_change = true;
break;
}
}
return true;
}
static bool radio_transmit_symbol(radio_transmit_entry *entry)
{
bool success;
switch (entry->radio_type) {
case RADIO_TYPE_SI4032:
success = radio_transmit_symbol_si4032(entry);
success = radio_transmit_symbol_si4032(entry, &radio_shared_state);
break;
case RADIO_TYPE_SI5351:
success = radio_transmit_symbol_si5351(entry);
success = radio_transmit_symbol_si5351(entry, &radio_shared_state);
break;
default:
return false;
}
if (success) {
radio_symbol_count_interrupt++;
radio_shared_state.radio_symbol_count_interrupt++;
}
return success;
}
static void radio_reset_transmit_delay_counter()
{
radio_post_transmit_delay_counter = RADIO_POST_TRANSMIT_DELAY_MS * SYSTEM_SCHEDULER_TIMER_TICKS_PER_SECOND / 1000;
}
static void radio_next_transmit_entry()
{
radio_current_transmit_entry_index = (radio_current_transmit_entry_index + 1) % RADIO_TRANSMIT_ENTRY_COUNT;
radio_current_transmit_entry = &radio_transmit_schedule[radio_current_transmit_entry_index];
radio_post_transmit_delay_counter = RADIO_POST_TRANSMIT_DELAY * SYSTEM_SCHEDULER_TIMER_TICKS_PER_SECOND / 1000;
do {
radio_current_transmit_entry_index = (radio_current_transmit_entry_index + 1) % radio_transmit_entry_count;
radio_current_transmit_entry = &radio_transmit_schedule[radio_current_transmit_entry_index];
} while (!radio_current_transmit_entry->enabled);
radio_reset_transmit_delay_counter();
}
void radio_handle_timer_tick()
{
if (radio_dma_transfer_active || radio_manual_transmit_active) {
if (!radio_module_initialized || radio_shared_state.radio_dma_transfer_active || radio_shared_state.radio_manual_transmit_active) {
return;
}
if (radio_next_symbol_counter > 0) {
radio_next_symbol_counter--;
}
if (radio_shared_state.radio_transmission_active) {
if (radio_next_symbol_counter > 0) {
radio_next_symbol_counter--;
}
if (radio_transmission_active && radio_should_transmit_next_symbol()) {
radio_transmit_next_symbol_flag = true;
radio_reset_next_symbol_counter();
if (radio_should_transmit_next_symbol()) {
radio_shared_state.radio_transmit_next_symbol_flag = true;
radio_reset_next_symbol_counter();
}
} else {
if (radio_post_transmit_delay_counter > 0) {
// TODO: use power saving
radio_post_transmit_delay_counter--;
}
}
if (!radio_transmission_active && radio_post_transmit_delay_counter > 0) {
radio_post_transmit_delay_counter--;
}
// TODO: specify which modes need time synchronization from GPS
// TODO: implement time sync
}
uint16_t symbol_delay = 823; // -> good around ~823 for a tight loop
bool radio_handle_time_sync()
{
// TODO: How to poll GPS time?
// TODO: Get time at millisecond precision!
// ubxg6010_request_gpstime();
gps_data gps;
ubxg6010_get_current_gps_data(&gps);
if (!gps.updated) {
// The GPS data has not been updated yet
return false;
}
if (false && gps.fix < 3) {
log_info("Skipping transmit entry that requires time sync, no GPS fix");
radio_next_transmit_entry();
return false;
}
uint32_t time_millis = gps.time_of_week_millis;
if (time_millis == radio_previous_time_sync_scheduled) {
// The GPS chip has not provided an updated time yet for some reason
return false;
}
uint32_t time_sync_offset_millis = radio_current_transmit_entry->time_sync_seconds_offset * 1000;
if (time_millis < time_sync_offset_millis) {
return false;
}
uint32_t time_sync_millis = radio_current_transmit_entry->time_sync_seconds * 1000;
uint32_t time_with_offset_millis = time_millis - time_sync_offset_millis;
uint32_t time_sync_period_millis = time_with_offset_millis % time_sync_millis;
bool is_scheduled_time = time_sync_period_millis < RADIO_TIME_SYNC_THRESHOLD_MS;
//log_info("time with offset: %lu, sync period: %lu, scheduled: %d\n", time_with_offset_millis, time_sync_period_millis, is_scheduled_time);
if (!is_scheduled_time) {
log_info("Time: %lu, GPS fix: %d - Waiting for time sync at every %d seconds with offset of %d\n", time_millis,
gps.fix,
radio_current_transmit_entry->time_sync_seconds,
radio_current_transmit_entry->time_sync_seconds_offset);
return false;
}
log_info("Time: %lu, GPS fix: %d, sync period: %lu - Scheduling transmit at %d seconds with offset of %d\n",
time_millis, gps.fix,
time_sync_period_millis, radio_current_transmit_entry->time_sync_seconds,
radio_current_transmit_entry->time_sync_seconds_offset);
radio_previous_time_sync_scheduled = time_millis;
return true;
}
void radio_handle_main_loop()
{
if (radio_post_transmit_delay_counter == 0) {
bool time_sync_required = radio_current_transmit_entry->time_sync_seconds > 0;
if (time_sync_required && !radio_shared_state.radio_transmission_active &&
!radio_shared_state.radio_transmission_finished) {
bool schedule_transmit = radio_handle_time_sync();
if (!schedule_transmit) {
// TODO: use power saving
delay_ms(100);
return;
}
radio_reset_transmit_delay_counter();
radio_start_transmit_entry = radio_current_transmit_entry;
} else if (!radio_shared_state.radio_transmission_active && radio_post_transmit_delay_counter == 0) {
#if defined(SEMIHOSTING_ENABLE) && defined(LOGGING_ENABLE)
telemetry_collect(&current_telemetry_data);
log_info("Battery: %d mV\n", current_telemetry_data.battery_voltage_millivolts);
log_info("Internal temperature: %ld C\n", current_telemetry_data.internal_temperature_celsius_100 / 100);
@ -607,59 +429,20 @@ void radio_handle_main_loop()
current_telemetry_data.gps.hours, current_telemetry_data.gps.minutes,
current_telemetry_data.gps.seconds);
log_info("Fix: %d, Sats: %d, OK packets: %d, Bad packets: %d\n",
current_telemetry_data.gps.fix, current_telemetry_data.gps.sats_raw,
current_telemetry_data.gps.fix, current_telemetry_data.gps.satellites_visible,
current_telemetry_data.gps.ok_packets, current_telemetry_data.gps.bad_packets);
log_info("Lat: %ld *1M, Lon: %ld *1M, Alt: %ld m\n",
current_telemetry_data.gps.lat_raw / 10, current_telemetry_data.gps.lon_raw / 10,
(current_telemetry_data.gps.alt_raw / 1000) * 3280 / 1000);
current_telemetry_data.gps.latitude_degrees_1000000 / 10,
current_telemetry_data.gps.longitude_degrees_1000000 / 10,
(current_telemetry_data.gps.altitude_mm / 1000) * 3280 / 1000);
#endif
radio_post_transmit_delay_counter = RADIO_POST_TRANSMIT_DELAY * SYSTEM_SCHEDULER_TIMER_TICKS_PER_SECOND / 1000;
radio_reset_transmit_delay_counter();
radio_start_transmit_entry = radio_current_transmit_entry;
}
if (radio_si4032_state_change) {
if (radio_manual_transmit_active) {
// TODO: Refactor this code for proper handling of APRS
fsk_encoder_api *fsk_encoder_api = radio_current_transmit_entry->fsk_encoder_api;
fsk_encoder *fsk_enc = &radio_current_transmit_entry->fsk_encoder;
log_info("Si4032 manual TX start: %d\n", symbol_delay);
system_disable_tick();
int8_t tone_index = 0;
uint32_t pwm_periods[2];
pwm_periods[0] = pwm_calculate_period(radio_current_fsk_tones[0].frequency_hz_100);
pwm_periods[1] = pwm_calculate_period(radio_current_fsk_tones[1].frequency_hz_100);
switch (radio_current_transmit_entry->data_mode) {
case RADIO_DATA_MODE_APRS:
do {
// radio_si4032_state_change = false;
pwm_timer_set_frequency(pwm_periods[tone_index]);
// radio_symbol_count_loop++;
delay_us(symbol_delay);
tone_index = fsk_encoder_api->next_tone(fsk_enc);
} while (tone_index >= 0);
//} while (radio_transmit_symbol(radio_current_transmit_entry));
radio_si4032_state_change = false;
radio_transmission_finished = true;
break;
default:
break;
}
system_enable_tick();
//symbol_delay += 1;
} else {
radio_si4032_state_change = false;
pwm_timer_set_frequency(radio_si4032_freq);
radio_symbol_count_loop++;
}
return;
}
if (radio_si5351_state_change) {
radio_si5351_state_change = false;
si5351_set_frequency(SI5351_CLOCK_CLK0, radio_si5351_freq);
return;
}
radio_handle_main_loop_si4032(radio_current_transmit_entry, &radio_shared_state);
radio_handle_main_loop_si5351(radio_current_transmit_entry, &radio_shared_state);
bool first_symbol = false;
if (radio_start_transmit_entry != NULL) {
@ -673,124 +456,61 @@ void radio_handle_main_loop()
return;
}
if (!radio_dma_transfer_active) {
if (!radio_shared_state.radio_dma_transfer_active) {
first_symbol = true;
radio_transmit_next_symbol_flag = true;
radio_shared_state.radio_transmit_next_symbol_flag = true;
}
}
if (radio_transmission_active && radio_transmit_next_symbol_flag) {
radio_transmit_next_symbol_flag = false;
bool success = radio_transmit_symbol(radio_current_transmit_entry);
if (!success) {
radio_transmission_finished = true;
}
if (first_symbol) {
radio_reset_next_symbol_counter();
if (radio_shared_state.radio_transmission_active && radio_shared_state.radio_transmit_next_symbol_flag) {
radio_shared_state.radio_transmit_next_symbol_flag = false;
if (!radio_shared_state.radio_manual_transmit_active) {
bool success = radio_transmit_symbol(radio_current_transmit_entry);
if (success) {
if (first_symbol) {
radio_reset_next_symbol_counter();
}
} else {
radio_shared_state.radio_transmission_finished = true;
}
}
}
if (radio_transmission_finished) {
radio_stop_transmit_entry = radio_current_transmit_entry;
if (radio_shared_state.radio_transmission_finished) {
end_tick = system_get_tick();
radio_transmission_finished = false;
}
if (radio_stop_transmit_entry != NULL) {
radio_stop_transmit(radio_stop_transmit_entry);
radio_stop_transmit_entry = NULL;
radio_stop_transmit(radio_current_transmit_entry);
radio_shared_state.radio_transmission_finished = false;
radio_next_transmit_entry();
log_info("Transmit stopped\n");
log_info("Symbol count (interrupt): %ld\n", radio_symbol_count_interrupt);
log_info("Symbol count (loop): %ld\n", radio_symbol_count_loop);
log_info("TX stop\n");
log_info("Symbol count (interrupt): %ld\n", radio_shared_state.radio_symbol_count_interrupt);
log_info("Symbol count (loop): %ld\n", radio_shared_state.radio_symbol_count_loop);
log_info("Total ticks: %ld\n", end_tick - start_tick);
log_info("Next symbol counter: %ld\n", radio_next_symbol_counter);
log_info("Symbol rate: %ld\n", radio_current_symbol_rate);
log_info("Symbol delay: %ld\n", radio_current_symbol_delay_ms_100);
log_info("Tone spacing: %ld\n", radio_current_tone_spacing_hz_100);
log_info("Symbol rate: %ld\n", radio_shared_state.radio_current_symbol_rate);
log_info("Symbol delay: %ld\n", radio_shared_state.radio_current_symbol_delay_ms_100);
log_info("Tone spacing: %ld\n", radio_shared_state.radio_current_tone_spacing_hz_100);
}
}
static uint16_t radio_fill_pwm_buffer(uint16_t offset, uint16_t length, uint16_t *buffer)
{
uint16_t count = 0;
for (uint16_t i = offset; i < (offset + length); i++, count++) {
uint32_t frequency = radio_next_symbol_si4032(radio_current_transmit_entry);
if (frequency == 0) {
// TODO: fill the other side of the buffer with zeroes too?
memset(buffer + offset, 0, (length - i) * sizeof(uint16_t));
break;
}
buffer[i] = pwm_calculate_period(frequency);
}
return count;
}
static bool radio_stop_dma_transfer_if_requested()
{
if (radio_dma_transfer_stop_after_counter > 0) {
radio_dma_transfer_stop_after_counter--;
} else if (radio_dma_transfer_stop_after_counter == 0) {
pwm_dma_stop();
radio_dma_transfer_stop_after_counter = -1;
radio_transmission_finished = true;
radio_dma_transfer_active = false;
return true;
}
return false;
}
uint16_t radio_handle_pwm_transfer_half(uint16_t buffer_size, uint16_t *buffer)
{
if (radio_stop_dma_transfer_if_requested()) {
return 0;
}
if (radio_transmission_finished) {
log_info("Should not be here, half-transfer!\n");
}
uint16_t length = radio_fill_pwm_buffer(0, buffer_size / 2, buffer);
if (radio_dma_transfer_stop_after_counter < 0 && length < buffer_size / 2) {
radio_dma_transfer_stop_after_counter = 2;
}
return length;
}
uint16_t radio_handle_pwm_transfer_full(uint16_t buffer_size, uint16_t *buffer)
{
if (radio_stop_dma_transfer_if_requested()) {
return 0;
}
if (radio_transmission_finished) {
log_info("Should not be here, transfer complete!\n");
}
uint16_t length = radio_fill_pwm_buffer(buffer_size / 2, buffer_size / 2, buffer);
if (radio_dma_transfer_stop_after_counter < 0 && length < buffer_size / 2) {
radio_dma_transfer_stop_after_counter = 2;
}
return length;
}
void radio_init()
{
memset(&current_telemetry_data, 0, sizeof(current_telemetry_data));
uint8_t count;
for (count = 0; !radio_transmit_schedule[count].end; count++);
radio_transmit_entry_count = count;
pwm_handle_dma_transfer_half = radio_handle_pwm_transfer_half;
pwm_handle_dma_transfer_full = radio_handle_pwm_transfer_full;
memset(&current_telemetry_data, 0, sizeof(current_telemetry_data));
radio_current_transmit_entry = &radio_transmit_schedule[radio_current_transmit_entry_index];
pwm_timer_init(100 * 100);
if (si4032_use_dma) {
pwm_data_timer_init();
pwm_dma_init();
while (!radio_current_transmit_entry->enabled) {
radio_current_transmit_entry_index = (radio_current_transmit_entry_index + 1) % radio_transmit_entry_count;
radio_current_transmit_entry = &radio_transmit_schedule[radio_current_transmit_entry_index];
}
radio_init_si4032();
radio_module_initialized = true;
}

Wyświetl plik

@ -0,0 +1,75 @@
#ifndef __RADIO_INTERNAL_H
#define __RADIO_INTERNAL_H
#include <stdint.h>
#include "payload.h"
#include "codecs/jtencode/jtencode.h"
#include "codecs/fsk/fsk.h"
typedef enum _radio_type {
RADIO_TYPE_SI4032 = 1,
RADIO_TYPE_SI5351,
} radio_type;
typedef enum _radio_data_mode {
RADIO_DATA_MODE_CW = 1,
RADIO_DATA_MODE_RTTY,
RADIO_DATA_MODE_APRS,
RADIO_DATA_MODE_WSPR,
RADIO_DATA_MODE_FT8,
RADIO_DATA_MODE_JT65,
RADIO_DATA_MODE_JT4,
RADIO_DATA_MODE_JT9,
RADIO_DATA_MODE_FSQ_2,
RADIO_DATA_MODE_FSQ_3,
RADIO_DATA_MODE_FSQ_4_5,
RADIO_DATA_MODE_FSQ_6,
} radio_data_mode;
typedef struct _radio_transmit_entry {
bool enabled;
bool end;
radio_type radio_type;
radio_data_mode data_mode;
uint16_t time_sync_seconds;
uint16_t time_sync_seconds_offset;
uint32_t frequency;
uint8_t tx_power;
uint32_t symbol_rate;
payload_encoder *payload_encoder;
fsk_encoder_api *fsk_encoder_api;
jtencode_mode_type jtencode_mode_type;
fsk_encoder fsk_encoder;
} radio_transmit_entry;
typedef struct _radio_module_state {
volatile bool radio_transmission_active;
volatile bool radio_transmission_finished;
volatile bool radio_transmit_next_symbol_flag;
volatile uint32_t radio_symbol_count_interrupt;
volatile uint32_t radio_symbol_count_loop;
volatile bool radio_dma_transfer_active;
volatile bool radio_manual_transmit_active;
fsk_tone *radio_current_fsk_tones;
int8_t radio_current_fsk_tone_count;
uint32_t radio_current_tone_spacing_hz_100;
uint32_t radio_current_symbol_rate;
uint32_t radio_current_symbol_delay_ms_100;
} radio_module_state;
extern radio_transmit_entry *radio_current_transmit_entry;
extern radio_module_state radio_shared_state;
#endif

Wyświetl plik

@ -0,0 +1,36 @@
#include <stdio.h>
#include <stdint.h>
#include "codecs/ax25/ax25.h"
#include "codecs/aprs/aprs.h"
#include "config.h"
#include "telemetry.h"
#include "log.h"
#include "radio_payload_aprs.h"
uint8_t aprs_packet[RADIO_PAYLOAD_MAX_LENGTH];
char aprs_comment[APRS_COMMENT_MAX_LENGTH];
const char *aprs_comment_format = " RS41ng test, time is %02d:%02d:%02d, locator %s, TOW %lu ms, gs %lu, hd %ld";
uint16_t radio_aprs_encode(uint8_t *payload, uint16_t length, telemetry_data *telemetry_data)
{
gps_data *gps = &telemetry_data->gps;
snprintf(aprs_comment, sizeof(aprs_comment),
aprs_comment_format,
gps->hours, gps->minutes, gps->seconds, telemetry_data->locator, gps->time_of_week_millis,
gps->ground_speed_cm_per_second, gps->heading_degrees_100000);
aprs_generate_position(aprs_packet, sizeof(aprs_packet), telemetry_data,
APRS_SYMBOL_TABLE, APRS_SYMBOL, false, aprs_comment);
log_debug("APRS packet: %s\n", aprs_packet);
return ax25_encode_packet_aprs(APRS_CALLSIGN, APRS_SSID, APRS_DESTINATION, APRS_DESTINATION_SSID, APRS_RELAYS,
(char *) aprs_packet, length, payload);
}
payload_encoder radio_aprs_payload_encoder = {
.encode = radio_aprs_encode,
};

Wyświetl plik

@ -0,0 +1,8 @@
#ifndef __RADIO_PAYLOAD_APRS_H
#define __RADIO_PAYLOAD_APRS_H
#include "payload.h"
extern payload_encoder radio_aprs_payload_encoder;
#endif

Wyświetl plik

@ -0,0 +1,24 @@
#include <stdio.h>
#include <string.h>
#include <stdint.h>
#include "radio_payload_ft8.h"
#include "config.h"
const bool ft8_locator_fixed_enabled = FT8_LOCATOR_FIXED_ENABLED;
uint16_t radio_ft8_encode(uint8_t *payload, uint16_t length, telemetry_data *telemetry_data)
{
char locator[5];
if (ft8_locator_fixed_enabled) {
strlcpy(locator, FT8_LOCATOR_FIXED, 4 + 1);
} else {
strlcpy(locator, telemetry_data->locator, 4 + 1);
}
return snprintf((char *) payload, length, "%s %s", FT8_CALLSIGN, locator);
}
payload_encoder radio_ft8_payload_encoder = {
.encode = radio_ft8_encode,
};

Wyświetl plik

@ -0,0 +1,8 @@
#ifndef __RADIO_PAYLOAD_FT8_H
#define __RADIO_PAYLOAD_FT8_H
#include "payload.h"
extern payload_encoder radio_ft8_payload_encoder;
#endif

Wyświetl plik

@ -0,0 +1,13 @@
#include <stdint.h>
#include "telemetry.h"
#include "radio_payload_wspr.h"
uint16_t radio_wspr_encode(uint8_t *payload, uint16_t length, telemetry_data *telemetry_data)
{
// Not used for WSPR
return 0;
}
payload_encoder radio_wspr_payload_encoder = {
.encode = radio_wspr_encode,
};

Wyświetl plik

@ -0,0 +1,8 @@
#ifndef __RADIO_PAYLOAD_WSPR_H
#define __RADIO_PAYLOAD_WSPR_H
#include "payload.h"
extern payload_encoder radio_wspr_payload_encoder;
#endif

290
src/radio_si4032.c 100644
Wyświetl plik

@ -0,0 +1,290 @@
#include <stdint.h>
#include <string.h>
#include "hal/system.h"
#include "hal/spi.h"
#include "hal/pwm.h"
#include "hal/delay.h"
#include "drivers/si4032/si4032.h"
#include "log.h"
#include "radio_si4032.h"
static bool si4032_use_dma = false;
// TODO: Add support for multiple APRS baud rates
uint16_t symbol_delay_bell_202_1200bps_us = 823;
static volatile bool radio_si4032_state_change = false;
static volatile uint32_t radio_si4032_freq = 0;
static volatile int8_t radio_dma_transfer_stop_after_counter = -1;
uint32_t precalculated_pwm_periods[FSK_TONE_COUNT_MAX];
uint16_t radio_si4032_fill_pwm_buffer(uint16_t offset, uint16_t length, uint16_t *buffer);
bool radio_start_transmit_si4032(radio_transmit_entry *entry, radio_module_state *shared_state)
{
uint16_t frequency_offset;
si4032_modulation_type modulation_type;
bool use_direct_mode;
switch (entry->data_mode) {
case RADIO_DATA_MODE_CW:
frequency_offset = 1;
modulation_type = SI4032_MODULATION_TYPE_OOK;
use_direct_mode = true;
break;
case RADIO_DATA_MODE_RTTY:
frequency_offset = 0;
modulation_type = SI4032_MODULATION_TYPE_NONE;
use_direct_mode = false;
break;
case RADIO_DATA_MODE_APRS:
frequency_offset = 0;
modulation_type = SI4032_MODULATION_TYPE_FSK;
use_direct_mode = true;
if (si4032_use_dma) {
radio_si4032_fill_pwm_buffer(0, PWM_TIMER_DMA_BUFFER_SIZE, pwm_timer_dma_buffer);
}
break;
default:
return false;
}
si4032_set_tx_frequency(((float) entry->frequency) / 1000000.0f);
si4032_set_tx_power(entry->tx_power * 7 / 100);
si4032_set_frequency_offset(frequency_offset);
si4032_set_modulation_type(modulation_type);
si4032_enable_tx();
if (use_direct_mode) {
spi_uninit();
pwm_timer_use(true);
pwm_timer_pwm_enable(true);
si4032_use_direct_mode(true);
}
switch (entry->data_mode) {
case RADIO_DATA_MODE_APRS:
if (si4032_use_dma) {
shared_state->radio_dma_transfer_active = true;
radio_dma_transfer_stop_after_counter = -1;
system_disable_tick();
pwm_dma_start();
} else {
shared_state->radio_manual_transmit_active = true;
}
break;
default:
break;
}
return true;
}
static uint32_t radio_next_symbol_si4032(radio_transmit_entry *entry, radio_module_state *shared_state)
{
switch (entry->data_mode) {
case RADIO_DATA_MODE_CW:
return 0;
case RADIO_DATA_MODE_RTTY:
return 0;
case RADIO_DATA_MODE_APRS: {
int8_t next_tone_index = entry->fsk_encoder_api->next_tone(&entry->fsk_encoder);
if (next_tone_index < 0) {
return 0;
}
return shared_state->radio_current_fsk_tones[next_tone_index].frequency_hz_100;
}
default:
return 0;
}
}
bool radio_transmit_symbol_si4032(radio_transmit_entry *entry, radio_module_state *shared_state)
{
uint32_t frequency = radio_next_symbol_si4032(entry, shared_state);
if (frequency == 0) {
return false;
}
radio_si4032_freq = frequency;
radio_si4032_state_change = true;
return true;
}
static void radio_handle_main_loop_manual_si4032(radio_transmit_entry *entry, radio_module_state *shared_state)
{
fsk_encoder_api *fsk_encoder_api = entry->fsk_encoder_api;
fsk_encoder *fsk_enc = &entry->fsk_encoder;
for (uint8_t i = 0; i < shared_state->radio_current_fsk_tone_count; i++) {
precalculated_pwm_periods[i] = pwm_calculate_period(shared_state->radio_current_fsk_tones[i].frequency_hz_100);
}
system_disable_tick();
switch (entry->data_mode) {
case RADIO_DATA_MODE_APRS: {
int8_t tone_index;
while ((tone_index = fsk_encoder_api->next_tone(fsk_enc)) >= 0) {
pwm_timer_set_frequency(precalculated_pwm_periods[tone_index]);
shared_state->radio_symbol_count_loop++;
delay_us(symbol_delay_bell_202_1200bps_us);
};
radio_si4032_state_change = false;
shared_state->radio_transmission_finished = true;
break;
}
default:
break;
}
system_enable_tick();
}
void radio_handle_main_loop_si4032(radio_transmit_entry *entry, radio_module_state *shared_state)
{
if (entry->radio_type != RADIO_TYPE_SI4032) {
return;
}
if (shared_state->radio_manual_transmit_active) {
radio_handle_main_loop_manual_si4032(entry, shared_state);
return;
}
if (radio_si4032_state_change) {
radio_si4032_state_change = false;
pwm_timer_set_frequency(radio_si4032_freq);
shared_state->radio_symbol_count_loop++;
}
}
bool radio_stop_transmit_si4032(radio_transmit_entry *entry, radio_module_state *shared_state)
{
bool use_direct_mode = false;
switch (entry->data_mode) {
case RADIO_DATA_MODE_CW:
use_direct_mode = true;
break;
case RADIO_DATA_MODE_RTTY:
use_direct_mode = false;
break;
case RADIO_DATA_MODE_APRS:
use_direct_mode = true;
if (si4032_use_dma) {
system_enable_tick();
}
break;
default:
break;
}
if (use_direct_mode) {
si4032_use_direct_mode(false);
pwm_timer_pwm_enable(false);
pwm_timer_use(false);
spi_init();
}
si4032_inhibit_tx();
switch (entry->data_mode) {
case RADIO_DATA_MODE_APRS:
if (si4032_use_dma) {
system_enable_tick();
}
break;
default:
break;
}
return true;
}
uint16_t radio_si4032_fill_pwm_buffer(uint16_t offset, uint16_t length, uint16_t *buffer)
{
uint16_t count = 0;
for (uint16_t i = offset; i < (offset + length); i++, count++) {
uint32_t frequency = radio_next_symbol_si4032(radio_current_transmit_entry, &radio_shared_state);
if (frequency == 0) {
// TODO: fill the other side of the buffer with zeroes too?
memset(buffer + offset, 0, (length - i) * sizeof(uint16_t));
break;
}
buffer[i] = pwm_calculate_period(frequency);
}
return count;
}
bool radio_si4032_stop_dma_transfer_if_requested(radio_module_state *shared_state)
{
if (radio_dma_transfer_stop_after_counter > 0) {
radio_dma_transfer_stop_after_counter--;
} else if (radio_dma_transfer_stop_after_counter == 0) {
pwm_dma_stop();
radio_dma_transfer_stop_after_counter = -1;
shared_state->radio_transmission_finished = true;
shared_state->radio_dma_transfer_active = false;
return true;
}
return false;
}
uint16_t radio_si4032_handle_pwm_transfer_half(uint16_t buffer_size, uint16_t *buffer)
{
if (radio_si4032_stop_dma_transfer_if_requested(&radio_shared_state)) {
return 0;
}
if (radio_shared_state.radio_transmission_finished) {
log_info("Should not be here, half-transfer!\n");
}
uint16_t length = radio_si4032_fill_pwm_buffer(0, buffer_size / 2, buffer);
if (radio_dma_transfer_stop_after_counter < 0 && length < buffer_size / 2) {
radio_dma_transfer_stop_after_counter = 2;
}
return length;
}
uint16_t radio_si4032_handle_pwm_transfer_full(uint16_t buffer_size, uint16_t *buffer)
{
if (radio_si4032_stop_dma_transfer_if_requested(&radio_shared_state)) {
return 0;
}
if (radio_shared_state.radio_transmission_finished) {
log_info("Should not be here, transfer complete!\n");
}
uint16_t length = radio_si4032_fill_pwm_buffer(buffer_size / 2, buffer_size / 2, buffer);
if (radio_dma_transfer_stop_after_counter < 0 && length < buffer_size / 2) {
radio_dma_transfer_stop_after_counter = 2;
}
return length;
}
void radio_init_si4032()
{
pwm_handle_dma_transfer_half = radio_si4032_handle_pwm_transfer_half;
pwm_handle_dma_transfer_full = radio_si4032_handle_pwm_transfer_full;
pwm_timer_init(100 * 100);
if (si4032_use_dma) {
pwm_data_timer_init();
pwm_dma_init();
}
}

12
src/radio_si4032.h 100644
Wyświetl plik

@ -0,0 +1,12 @@
#ifndef __RADIO_SI4032_H
#define __RADIO_SI4032_H
#include "radio_internal.h"
bool radio_start_transmit_si4032(radio_transmit_entry *entry, radio_module_state *shared_state);
bool radio_transmit_symbol_si4032(radio_transmit_entry *entry, radio_module_state *shared_state);
void radio_handle_main_loop_si4032(radio_transmit_entry *entry, radio_module_state *shared_state);
bool radio_stop_transmit_si4032(radio_transmit_entry *entry, radio_module_state *shared_state);
void radio_init_si4032();
#endif

58
src/radio_si5351.c 100644
Wyświetl plik

@ -0,0 +1,58 @@
#include <stdint.h>
#include "si5351_handler.h"
#include "radio_si5351.h"
#include "log.h"
static volatile bool radio_si5351_state_change = false;
static volatile uint64_t radio_si5351_freq = 0;
bool radio_start_transmit_si5351(radio_transmit_entry *entry, radio_module_state *shared_state)
{
si5351_set_drive_strength(SI5351_CLOCK_CLK0, entry->tx_power * 3 / 100);
si5351_set_frequency(SI5351_CLOCK_CLK0, ((uint64_t) entry->frequency) * 100ULL);
si5351_output_enable(SI5351_CLOCK_CLK0, true);
return true;
}
bool radio_transmit_symbol_si5351(radio_transmit_entry *entry, radio_module_state *shared_state)
{
switch (entry->data_mode) {
case RADIO_DATA_MODE_CW:
return false;
default: {
int8_t next_tone_index = entry->fsk_encoder_api->next_tone(&entry->fsk_encoder);
if (next_tone_index < 0) {
return false;
}
log_trace("Tone: %d\n", next_tone_index);
uint64_t frequency =
((uint64_t) entry->frequency) * 100UL + (next_tone_index * shared_state->radio_current_tone_spacing_hz_100);
radio_si5351_freq = frequency;
radio_si5351_state_change = true;
break;
}
}
return true;
}
void radio_handle_main_loop_si5351(radio_transmit_entry *entry, radio_module_state *shared_state)
{
if (entry->radio_type != RADIO_TYPE_SI5351) {
return;
}
if (radio_si5351_state_change) {
radio_si5351_state_change = false;
si5351_set_frequency(SI5351_CLOCK_CLK0, radio_si5351_freq);
}
}
bool radio_stop_transmit_si5351(radio_transmit_entry *entry, radio_module_state *shared_state)
{
si5351_output_enable(SI5351_CLOCK_CLK0, false);
return true;
}

11
src/radio_si5351.h 100644
Wyświetl plik

@ -0,0 +1,11 @@
#ifndef __RADIO_SI5351_H
#define __RADIO_SI5351_H
#include "radio_internal.h"
bool radio_start_transmit_si5351(radio_transmit_entry *entry, radio_module_state *shared_state);
bool radio_transmit_symbol_si5351(radio_transmit_entry *entry, radio_module_state *shared_state);
void radio_handle_main_loop_si5351(radio_transmit_entry *entry, radio_module_state *shared_state);
bool radio_stop_transmit_si5351(radio_transmit_entry *entry, radio_module_state *shared_state);
#endif

Wyświetl plik

@ -1,118 +1,135 @@
/**************************************************************************//*****
* @file stdio.c
* @brief Implementation of newlib syscall
********************************************************************************/
#include <sys/types.h>
#include <sys/stat.h>
#include "log.h"
#include "semihosting.h"
#undef errno
extern int errno;
extern int _end;
/*This function is used for handle heap option*/
__attribute__ ((used))
caddr_t _sbrk ( int incr )
{
static unsigned char *heap = NULL;
unsigned char *prev_heap;
if (heap == NULL) {
heap = (unsigned char *)&_end;
}
prev_heap = heap;
heap += incr;
return (caddr_t) prev_heap;
}
__attribute__ ((used))
int link(char *old, char *new)
{
return -1;
}
__attribute__ ((used))
int _close(int file)
{
return -1;
}
__attribute__ ((used))
int _fstat(int file, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
}
__attribute__ ((used))
int _isatty(int file)
{
return 1;
}
__attribute__ ((used))
int _lseek(int file, int ptr, int dir)
{
return 0;
}
/*Low layer read(input) function*/
__attribute__ ((used))
int _read(int file, char *ptr, int len)
{
#if 0
//user code example
int i;
(void)file;
for(i = 0; i < len; i++)
{
// UART_GetChar is user's basic input function
*ptr++ = UART_GetChar();
}
#endif
return len;
}
/*Low layer write(output) function*/
__attribute__ ((used))
int _write(int file, char *ptr, int len)
{
#ifdef SEMIHOSTING_ENABLE
openocd_write(file, len, ptr);
#endif
#if 0
//user code example
int i;
(void)file;
for(i = 0; i < len; i++)
{
// UART_PutChar is user's basic output function
UART_PutChar(*ptr++);
}
#endif
return len;
}
__attribute__ ((used))
void abort(void)
{
/* Abort called */
while(1);
}
/* --------------------------------- End Of File ------------------------------ */
/**************************************************************************//*****
* @file stdio.c
* @brief Implementation of newlib syscall
********************************************************************************/
#include <sys/types.h>
#include <sys/stat.h>
#include <errno.h>
#include "log.h"
#include "semihosting.h"
#undef errno
extern int errno;
extern int _end;
extern int __HeapLimit;
/*This function is used for handle heap option*/
__attribute__ ((used))
caddr_t _sbrk ( int incr )
{
static unsigned char *heap = NULL;
unsigned char *prev_heap;
if (heap == NULL) {
heap = (unsigned char *)&_end;
}
prev_heap = heap;
if (heap + incr > (unsigned char *) &__HeapLimit) {
#ifdef SEMIHOSTING_ENABLE
extern void abort(void);
openocd_write(1, 15, "Out of memory!\n");
abort();
#else
errno = ENOMEM;
return (caddr_t) -1;
#endif
}
// Need to align heap to word boundary, else will get
// hard faults on Cortex-M0. So we assume that heap starts on
// word boundary, hence make sure we always add a multiple of
// 4 to it.
incr = (incr + 7) & (~7); // align value to 8
heap += incr;
return (caddr_t) prev_heap;
}
__attribute__ ((used))
int link(char *old, char *new)
{
return -1;
}
__attribute__ ((used))
int _close(int file)
{
return -1;
}
__attribute__ ((used))
int _fstat(int file, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
}
__attribute__ ((used))
int _isatty(int file)
{
return 1;
}
__attribute__ ((used))
int _lseek(int file, int ptr, int dir)
{
return 0;
}
/*Low layer read(input) function*/
__attribute__ ((used))
int _read(int file, char *ptr, int len)
{
#if 0
//user code example
int i;
(void)file;
for(i = 0; i < len; i++)
{
// UART_GetChar is user's basic input function
*ptr++ = UART_GetChar();
}
#endif
return len;
}
/*Low layer write(output) function*/
__attribute__ ((used))
int _write(int file, char *ptr, int len)
{
#ifdef SEMIHOSTING_ENABLE
openocd_write(file, len, ptr);
#endif
#if 0
//user code example
int i;
(void)file;
for(i = 0; i < len; i++)
{
// UART_PutChar is user's basic output function
UART_PutChar(*ptr++);
}
#endif
return len;
}
__attribute__ ((used))
void abort(void)
{
/* Abort called */
while(1);
}
/* --------------------------------- End Of File ------------------------------ */

Wyświetl plik

@ -16,5 +16,6 @@ void telemetry_collect(telemetry_data *data)
}
ubxg6010_get_current_gps_data(&data->gps);
locator_from_lonlat(data->gps.lon_raw, data->gps.lat_raw, LOCATOR_PAIR_COUNT_FULL, data->locator);
locator_from_lonlat(data->gps.longitude_degrees_1000000, data->gps.latitude_degrees_1000000,
LOCATOR_PAIR_COUNT_FULL, data->locator);
}

Wyświetl plik

@ -17,14 +17,14 @@ int main(void)
memset(&telemetry, 0, sizeof(telemetry_data));
uint8_t aprs_packet[256];
size_t aprs_length = aprs_generate_position_without_timestamp(
aprs_packet, sizeof(aprs_packet), &telemetry, APRS_SYMBOL_TABLE, APRS_SYMBOL, APRS_COMMENT);
size_t aprs_length = aprs_generate_position(
aprs_packet, sizeof(aprs_packet), &telemetry, APRS_SYMBOL_TABLE, APRS_SYMBOL, false, APRS_COMMENT);
uint8_t payload[256];
size_t payload_length = ax25_encode_packet_aprs(APRS_CALLSIGN, APRS_SSID, APRS_DESTINATION, APRS_DESTINATION_SSID, APRS_RELAYS,
(char *) aprs_packet, aprs_length, payload);
printf("Full payload length: %d\n", payload_length);
printf("Full payload length: %ld\n", payload_length);
for (int i = 0; i < payload_length; i++) {
uint8_t c = payload[i];
@ -37,19 +37,6 @@ int main(void)
printf("\n");
//uint8_t payload[] = { 0x7e, 0x82, 0xa0, 0xb4, 'h', 'b', 0x9c, 0x00, 0x7e};
// 0x7e: 0 1 1 1 1 1 1 0
// 0x82: 0 1 0 0 0 0 0 1
// 0xa0: 0 0 0 0 0 1 0 1
// 0xb4: 0 0 1 0 1 1 0 1
//uint8_t payload[] = { 0x7e, 0x3f, 0x7f };
// 1 1 1 1 1 1 0 0
// N N N N N S N C C
// 1 1 1 1 1 1 1 0
// N N N N N S N N C
bell_encoder_set_data(&fsk_encoder, sizeof(payload), payload);
size_t index = 0;