Merged remote-tracking branch 'upstream/master'

This commit is contained in:
furrtek 2015-11-18 22:01:48 +01:00
commit 835d581e6c
135 changed files with 8512 additions and 7734 deletions

24
.travis.yml Normal file
View File

@ -0,0 +1,24 @@
language: cpp
cache: apt
before_install:
- sudo add-apt-repository ppa:terry.guo/gcc-arm-embedded -y
- sudo apt-get update -qq
- sudo apt-get install -y gcc-arm-none-eabi
before_script:
- export CC="arm-none-eabi-gcc"
- export CXX="arm-none-eabi-g++"
script:
# TODO: Introduce top-level Makefile, this is lame.
- pushd firmware/
- make release
- popd
addons:
artifacts:
paths:
- $(ls firmware/portapack-h1-firmware-*.tar.bz2 | tr "\n" ":")
- $(ls firmware/portapack-h1-firmware-*.zip | tr "\n" ":")

View File

@ -2,19 +2,19 @@
The PortaPack H1 makes the [HackRF One software-defined radio](http://greatscottgadgets.com/hackrf/) portable. It adds an LCD touchscreen, user interface navigation controls, audio output and input, micro SD card slot, and real-time clock battery backup.
As it name implies, HAVOC is a firmware aimed towards serious fun. Don't use it. In fact, we never did.
As its name implies, HAVOC is a firmware aimed towards serious fun. Don't use it. We never did.
Fork features:
* RDS (Radio Data System) basic group forming and transmit
* LCR (Language de Commande Routier) basic message forming
* Fully configurable AFSK transmit
* "Play Dead" in case of emergency
* Fully configurable Jammer
Todo:
* AFSK receiver
* Moltonel (tone detector/scanner)
* Whistle (tone generator)
* Signal drowner (jammer)
* Wireless microphone transmit
* CTCSS talkie transmit
* Play wave files from µSD

Binary file not shown.

After

Width:  |  Height:  |  Size: 24 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 19 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 11 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 12 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 9.0 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 24 KiB

View File

@ -23,11 +23,6 @@ PATH_BOOTSTRAP=bootstrap
PATH_APPLICATION=application
PATH_BASEBAND=baseband
# TODO: Pass these (as #defines?) to Makefiles, use values in code.
PAD_BOOTSTRAP=0x10000
PAD_HACKRF_FIRMWARE=65536
PAD_BASEBAND=0x20000
TARGET=portapack-h1-firmware
TARGET_BOOTSTRAP=$(PATH_BOOTSTRAP)/bootstrap
@ -35,10 +30,12 @@ TARGET_HACKRF_FIRMWARE=hackrf_one_usb_ram
TARGET_APPLICATION=$(PATH_APPLICATION)/build/application
TARGET_BASEBAND=$(PATH_BASEBAND)/build/baseband
MAKE_SPI_IMAGE=tools/make_spi_image.py
DFU_HACKRF=hackrf_one_usb_ram.dfu
LICENSE=../LICENSE
REVISION=$(shell git log -n 1 --format=%h)
GIT_REVISION=$(shell git log -n 1 --format=%h)
CP=arm-none-eabi-objcopy
@ -47,8 +44,8 @@ all: $(TARGET).bin
release: $(TARGET).bin $(DFU_HACKRF) $(LICENSE)
# TODO: Bad hack to fix location of LICENSE file for tar.
cp $(LICENSE) LICENSE
tar -c -j -f $(TARGET)-$(REVISION).tar.bz2 $(TARGET).bin $(DFU_HACKRF) LICENSE
zip -9 -q $(TARGET)-$(REVISION).zip $(TARGET).bin $(DFU_HACKRF) LICENSE
tar -c -j -f $(TARGET)-$(GIT_REVISION).tar.bz2 $(TARGET).bin $(DFU_HACKRF) LICENSE
zip -9 -q $(TARGET)-$(GIT_REVISION).zip $(TARGET).bin $(DFU_HACKRF) LICENSE
rm -f LICENSE
program: $(TARGET).bin
@ -56,36 +53,31 @@ program: $(TARGET).bin
sleep 1s
hackrf_spiflash -w $(TARGET).bin
$(TARGET).bin: $(TARGET_BOOTSTRAP)_pad.bin $(TARGET_HACKRF_FIRMWARE)_dfu_pad.bin $(TARGET_BASEBAND)_pad.bin $(TARGET_APPLICATION).bin
cat $(TARGET_BOOTSTRAP)_pad.bin $(TARGET_HACKRF_FIRMWARE)_dfu_pad.bin $(TARGET_BASEBAND)_pad.bin $(TARGET_APPLICATION).bin >$(TARGET).bin
$(TARGET).bin: $(MAKE_SPI_IMAGE) $(TARGET_BOOTSTRAP).bin $(TARGET_HACKRF_FIRMWARE).dfu $(TARGET_BASEBAND).bin $(TARGET_APPLICATION).bin
$(MAKE_SPI_IMAGE) $(TARGET_BOOTSTRAP).bin $(TARGET_HACKRF_FIRMWARE).dfu $(TARGET_BASEBAND).bin $(TARGET_APPLICATION).bin $(TARGET).bin
$(TARGET_BOOTSTRAP)_pad.bin: $(TARGET_BOOTSTRAP).elf
$(CP) -O binary --pad-to $(PAD_BOOTSTRAP) $(TARGET_BOOTSTRAP).elf $(TARGET_BOOTSTRAP)_pad.bin
$(TARGET_BOOTSTRAP).bin: $(TARGET_BOOTSTRAP).elf
$(CP) -O binary $(TARGET_BOOTSTRAP).elf $(TARGET_BOOTSTRAP).bin
$(TARGET_HACKRF_FIRMWARE)_dfu_pad.bin: $(TARGET_HACKRF_FIRMWARE).dfu
# TODO: Not confident this is reliable. It certainly won't work on Windows.
# Pad the .dfu with zeros, then truncate to the desired length.
head -c $(PAD_HACKRF_FIRMWARE) /dev/zero | cat $(TARGET_HACKRF_FIRMWARE).dfu - | head -c $(PAD_HACKRF_FIRMWARE) >$(TARGET_HACKRF_FIRMWARE)_dfu_pad.bin
$(TARGET_BASEBAND)_pad.bin: $(TARGET_BASEBAND).elf
$(CP) -O binary --pad-to $(PAD_BASEBAND) $(TARGET_BASEBAND).elf $(TARGET_BASEBAND)_pad.bin
$(TARGET_BASEBAND).bin: $(TARGET_BASEBAND).elf
$(CP) -O binary $(TARGET_BASEBAND).elf $(TARGET_BASEBAND).bin
$(TARGET_APPLICATION).bin: $(TARGET_APPLICATION).elf
$(CP) -O binary $(TARGET_APPLICATION).elf $(TARGET_APPLICATION).bin
$(TARGET_BASEBAND).elf: always_check
@$(MAKE) -s -C $(PATH_BASEBAND)
@$(MAKE) -s -e GIT_REVISION=$(GIT_REVISION) -C $(PATH_BASEBAND)
$(TARGET_APPLICATION).elf: always_check
@$(MAKE) -s -C $(PATH_APPLICATION)
@$(MAKE) -s -e GIT_REVISION=$(GIT_REVISION) -C $(PATH_APPLICATION)
$(TARGET_BOOTSTRAP).elf: always_check
@$(MAKE) -s -C $(PATH_BOOTSTRAP)
@$(MAKE) -s -e GIT_REVISION=$(GIT_REVISION) -C $(PATH_BOOTSTRAP)
clean:
rm -f $(TARGET).bin
rm -f $(TARGET_BOOTSTRAP)_pad.bin
rm -f $(TARGET_BASEBAND)_pad.bin
rm -f $(TARGET_BOOTSTRAP).bin
rm -f $(TARGET_BASEBAND).bin
rm -f $(TARGET_APPLICATION).bin
$(MAKE) -C $(PATH_BASEBAND) clean
$(MAKE) -C $(PATH_APPLICATION) clean

View File

@ -112,8 +112,7 @@ CSRC = $(PORTSRC) \
$(HALSRC) \
$(PLATFORMSRC) \
$(BOARDSRC) \
$(FATFSSRC) \
$(CHIBIOS)/os/various/evtimer.c
$(FATFSSRC)
# C++ sources that can be compiled in ARM or THUMB mode depending on the global
@ -122,6 +121,7 @@ CPPSRC = main.cpp \
irq_ipc.cpp \
irq_lcd_frame.cpp \
irq_controls.cpp \
irq_rtc.cpp \
event.cpp \
message_queue.cpp \
hackrf_hal.cpp \
@ -166,13 +166,16 @@ CPPSRC = main.cpp \
ui_whistle.cpp \
ui_jammer.cpp \
ui_afsksetup.cpp \
ui_baseband_stats_view.cpp \
ui_console.cpp \
ui_receiver.cpp \
ui_spectrum.cpp \
receiver_model.cpp \
transmitter_model.cpp \
spectrum_color_lut.cpp \
ais_baseband.cpp \
../common/utility.cpp \
../common/chibios_cpp.cpp \
../common/debug.cpp \
../common/gcc.cpp \
m4_startup.cpp \
@ -218,6 +221,9 @@ INCDIR = ../common $(PORTINC) $(KERNINC) $(TESTINC) \
# Compiler settings
#
# TODO: Entertain using MCU=cortex-m0.small-multiply for LPC43xx M0 core.
# However, on GCC-ARM-Embedded 4.9 2015q2, it seems to produce non-functional
# binaries.
MCU = cortex-m0
#TRGT = arm-elf-
@ -260,7 +266,8 @@ CPPWARN = -Wall -Wextra
# TODO: Switch -DCRT0_INIT_DATA depending on load from RAM or SPIFI?
# NOTE: _RANDOM_TCC to kill a GCC 4.9.3 error with std::max argument types
DDEFS = -DLPC43XX -DLPC43XX_M0 -D__NEWLIB__ -DHACKRF_ONE \
-DTOOLCHAIN_GCC -DTOOLCHAIN_GCC_ARM -D_RANDOM_TCC=0
-DTOOLCHAIN_GCC -DTOOLCHAIN_GCC_ARM -D_RANDOM_TCC=0 \
-DGIT_REVISION=\"$(GIT_REVISION)\"
# List all default ASM defines here, like -D_DEBUG=1
DADEFS =

View File

@ -163,24 +163,16 @@ constexpr si5351::MultisynthFractional si5351_ms_10m {
};
constexpr auto si5351_ms_3_10m_reg = si5351_ms_10m.reg(3);
constexpr si5351::MultisynthFractional si5351_ms_50m {
constexpr si5351::MultisynthFractional si5351_ms_40m {
.f_src = si5351_vco_f,
.a = 16,
.a = 20,
.b = 0,
.c = 1,
.r_div = 0,
};
// constexpr si5351::MultisynthFractional si5351_ms_40m {
// .f_src = si5351_vco_f,
// .a = 20,
// .b = 0,
// .c = 1,
// .r_div = 0,
// };
constexpr auto si5351_ms_rffc5072 = si5351_ms_50m;
constexpr auto si5351_ms_max2837 = si5351_ms_50m;
constexpr auto si5351_ms_rffc5072 = si5351_ms_40m;
constexpr auto si5351_ms_max2837 = si5351_ms_40m;
constexpr auto si5351_ms_4_reg = si5351_ms_rffc5072.reg(clock_generator_output_first_if);
constexpr auto si5351_ms_5_reg = si5351_ms_max2837.reg(clock_generator_output_second_if);
@ -232,7 +224,7 @@ constexpr ClockControls si5351_clock_control_common {
ClockControl::CLK_IDRV_8mA | ClockControl::CLK_SRC_MS_Self | ClockControl::CLK_INV_Normal | ClockControl::MS_INT_Integer | ClockControl::CLK_PDN_Power_Off,
ClockControl::CLK_IDRV_8mA | ClockControl::CLK_SRC_MS_Self | ClockControl::CLK_INV_Normal | ClockControl::MS_INT_Integer | ClockControl::CLK_PDN_Power_Off,
ClockControl::CLK_IDRV_6mA | ClockControl::CLK_SRC_MS_Self | ClockControl::CLK_INV_Normal | ClockControl::MS_INT_Integer | ClockControl::CLK_PDN_Power_Off,
ClockControl::CLK_IDRV_2mA | ClockControl::CLK_SRC_MS_Self | ClockControl::CLK_INV_Normal | ClockControl::MS_INT_Integer | ClockControl::CLK_PDN_Power_Off,
ClockControl::CLK_IDRV_2mA | ClockControl::CLK_SRC_MS_Self | ClockControl::CLK_INV_Normal | ClockControl::MS_INT_Fractional | ClockControl::CLK_PDN_Power_Off,
ClockControl::CLK_IDRV_6mA | ClockControl::CLK_SRC_MS_Self | ClockControl::CLK_INV_Normal | ClockControl::MS_INT_Integer | ClockControl::CLK_PDN_Power_Off,
};
@ -368,6 +360,23 @@ void ClockManager::set_sampling_frequency(const uint32_t frequency) {
clock_generator.set_ms_frequency(clock_generator_output_codec, frequency * 2, si5351_vco_f, 1);
}
void ClockManager::set_reference_ppb(const int32_t ppb) {
constexpr uint32_t pll_multiplier = si5351_pll_xtal_25m.a;
constexpr uint32_t denominator = 1000000 / pll_multiplier;
const uint32_t new_a = (ppb >= 0) ? pll_multiplier : (pll_multiplier - 1);
const uint32_t new_b = (ppb >= 0) ? (ppb / 1000) : (denominator + (ppb / 1000));
const uint32_t new_c = (ppb == 0) ? 1 : denominator;
const si5351::PLL pll {
.f_in = si5351_inputs.f_xtal,
.a = new_a,
.b = new_b,
.c = new_c,
};
const auto pll_a_reg = pll.reg(0);
clock_generator.write(pll_a_reg);
}
void ClockManager::change_clock_configuration(const cgu::CLK_SEL clk_sel) {
/* If starting PLL1, turn on the clock feeding GP_CLKIN */
if( clk_sel == cgu::CLK_SEL::PLL1 ) {

View File

@ -62,6 +62,8 @@ public:
void set_sampling_frequency(const uint32_t frequency);
void set_reference_ppb(const int32_t ppb);
private:
I2C& i2c0;
si5351::Si5351& clock_generator;

View File

@ -26,7 +26,6 @@
constexpr auto EVT_MASK_RTC_TICK = EVENT_MASK(0);
constexpr auto EVT_MASK_LCD_FRAME_SYNC = EVENT_MASK(1);
constexpr auto EVT_MASK_SD_CARD_PRESENT = EVENT_MASK(2);
constexpr auto EVT_MASK_SWITCHES = EVENT_MASK(3);
constexpr auto EVT_MASK_ENCODER = EVENT_MASK(4);
constexpr auto EVT_MASK_TOUCH = EVENT_MASK(5);

View File

@ -36,7 +36,7 @@
/ 3: f_lseek() function is removed in addition to 2. */
#define _USE_STRFUNC 0
#define _USE_STRFUNC 1
/* This option switches string functions, f_gets(), f_putc(), f_puts() and
/ f_printf().
/

View File

@ -79,43 +79,48 @@ static touch::Frame touch_frame;
static uint32_t touch_debounce = 0;
static uint32_t touch_debounce_mask = (1U << 1) - 1;
static bool touch_stable = false;
static bool touch_detected = false;
static bool touch_cycle = false;
static bool touch_update() {
const auto samples = touch::adc::get();
const auto current_phase = touch_pins_configs[touch_phase];
if( current_phase == portapack::IO::TouchPinsConfig::WaitTouch ) {
/* Debounce touches. */
const bool touch_raw = (samples.yp < touch::touch_threshold) && (samples.yn < touch::touch_threshold);
touch_debounce = (touch_debounce << 1) | (touch_raw ? 1U : 0U);
touch_stable = ((touch_debounce & touch_debounce_mask) == touch_debounce_mask);
} else {
if( touch_stable ) {
switch(current_phase) {
case portapack::IO::TouchPinsConfig::SensePressure:
temp_frame.pressure += samples;
break;
case portapack::IO::TouchPinsConfig::SenseX:
temp_frame.x += samples;
break;
case portapack::IO::TouchPinsConfig::SenseY:
temp_frame.y += samples;
break;
default:
break;
switch(current_phase) {
case portapack::IO::TouchPinsConfig::WaitTouch:
{
/* Debounce touches. */
const bool touch_raw = (samples.yp < touch::touch_threshold) && (samples.yn < touch::touch_threshold);
touch_debounce = (touch_debounce << 1) | (touch_raw ? 1U : 0U);
touch_detected = ((touch_debounce & touch_debounce_mask) == touch_debounce_mask);
if( !touch_detected && !touch_cycle ) {
return false;
}
}
break;
case portapack::IO::TouchPinsConfig::SensePressure:
temp_frame.pressure += samples;
break;
case portapack::IO::TouchPinsConfig::SenseX:
temp_frame.x += samples;
break;
case portapack::IO::TouchPinsConfig::SenseY:
temp_frame.y += samples;
break;
default:
break;
}
touch_phase++;
if( touch_phase >= touch_pins_configs.size() ) {
/* New iteration, calculate values and flag touch event */
touch_phase = 0;
temp_frame.touch = touch_stable;
temp_frame.touch = touch_detected;
touch_cycle = touch_detected;
touch_frame = temp_frame;
temp_frame = {};
return true;

View File

@ -19,26 +19,32 @@
* Boston, MA 02110-1301, USA.
*/
#include "access_code_correlator.hpp"
#include "irq_rtc.hpp"
void AccessCodeCorrelator::configure(
const uint32_t new_code,
const size_t new_code_length,
const size_t new_maximum_hamming_distance
) {
if( new_code_length <= 32 ) {
code = new_code;
mask = mask_value(new_code_length);
maximum_hamming_distance = new_maximum_hamming_distance;
}
#include "ch.h"
#include "lpc43xx_cpp.hpp"
using namespace lpc43xx;
#include "event.hpp"
void rtc_interrupt_enable() {
rtc::interrupt::enable_second_inc();
nvicEnableVector(RTC_IRQn, CORTEX_PRIORITY_MASK(LPC_RTC_IRQ_PRIORITY));
}
extern "C" {
CH_IRQ_HANDLER(RTC_IRQHandler) {
CH_IRQ_PROLOGUE();
chSysLockFromIsr();
events_flag_isr(EVT_MASK_RTC_TICK);
chSysUnlockFromIsr();
rtc::interrupt::clear_all();
CH_IRQ_EPILOGUE();
}
bool AccessCodeCorrelator::execute(
const uint_fast8_t in
) {
history = (history << 1) | (in & 1);
const auto delta_bits = (history ^ code) & mask;
//const size_t count = __builtin_popcountll(delta_bits);
const size_t count = __builtin_popcountl(delta_bits);
return (count <= maximum_hamming_distance);
}

View File

@ -0,0 +1,27 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __IPC_RTC_H__
#define __IPC_RTC_H__
void rtc_interrupt_enable();
#endif/*__IPC_RTC_H__*/

View File

@ -23,6 +23,9 @@
#include "hal.h"
#include "message.hpp"
#include "portapack_shared_memory.hpp"
#include <cstring>
/* TODO: OK, this is cool, but how do I put the M4 to sleep so I can switch to
@ -32,17 +35,20 @@
* I suppose I could force M4MEMMAP to an invalid memory reason which would
* cause an exception and effectively halt the M4. But that feels gross.
*/
void m4_init(const portapack::spi_flash::region_t from, void* const to) {
//m4txevent_interrupt_disable();
void m4_init(const portapack::spi_flash::region_t from, const portapack::memory::region_t to) {
/* Initialize M4 code RAM */
std::memcpy(to, from.base_address(), from.size);
std::memcpy(reinterpret_cast<void*>(to.base()), from.base(), from.size);
/* M4 core is assumed to be sleeping with interrupts off, so we can mess
* with its address space and RAM without concern.
*/
LPC_CREG->M4MEMMAP = reinterpret_cast<uint32_t>(to);
LPC_CREG->M4MEMMAP = to.base();
/* Reset M4 core */
LPC_RGU->RESET_CTRL[0] = (1 << 13);
}
void m4_request_shutdown() {
ShutdownMessage shutdown_message;
shared_memory.baseband_queue.push(shutdown_message);
}

View File

@ -24,8 +24,10 @@
#include <cstddef>
#include "memory_map.hpp"
#include "spi_image.hpp"
void m4_init(const portapack::spi_flash::region_t from, void* const to);
void m4_init(const portapack::spi_flash::region_t from, const portapack::memory::region_t to);
void m4_request_shutdown();
#endif/*__M4_STARTUP_H__*/

View File

@ -60,6 +60,7 @@ using namespace lpc43xx;
#include "irq_ipc.hpp"
#include "irq_lcd_frame.hpp"
#include "irq_controls.hpp"
#include "irq_rtc.hpp"
#include "event.hpp"
@ -73,100 +74,9 @@ using namespace lpc43xx;
#include <string.h>
/* From ChibiOS crt0.c:
* Two stacks available for Cortex-M, main stack or process stack.
*
* Thread mode: Used to execute application software. The processor
* enters Thread mode when it comes out of reset.
* Handler mode: Used to handle exceptions. The processor returns to
* Thread mode when it has finished all exception processing.
*
* ChibiOS configures the Cortex-M in dual-stack mode. (CONTROL[1]=1)
* When CONTROL[1]=1, PSP is used when the processor is in Thread mode.
*
* MSP is always used when the processor is in Handler mode.
*
* __main_stack_size__ : 0x2000???? - 0x2000???? =
* Used for exception handlers. Yes, really.
* __process_stack_size__ : 0x2000???? - 0x2000???? =
* Used by main().
*
* After chSysInit(), the current instructions stream (usually main())
* becomes the main thread.
*/
#include "sd_card.hpp"
#if 0
static const SPIConfig ssp_config_w25q80bv = {
.end_cb = NULL,
.ssport = ?,
.sspad = ?,
.cr0 =
CR0_CLOCKRATE()
| ?
| ?
,
.cpsr = ?,
};
static spi_bus_t ssp0 = {
.obj = &SPID1,
.config = &ssp_config_w25q80bv,
.start = spi_chibi_start,
.stop = spi_chibi_stop,
.transfer = spi_chibi_transfer,
.transfer_gather = spi_chibi_transfer_gather,
};
#endif
/* ChibiOS initialization sequence:
* ResetHandler:
* Initialize FPU (if present)
* Initialize stacks (fill with pattern)
* __early_init()
* Enable extra processor exceptions for debugging
* Init data segment (flash -> data)
* Initialize BSS (fill with 0)
* __late_init()
* reset_peripherals()
* halInit()
* hal_lld_init()
* Init timer 3 as cycle counter
* Init RIT as SysTick
* palInit()
* gptInit()
* i2cInit()
* sdcInit()
* spiInit()
* rtcInit()
* boardInit()
* chSysInit()
* Constructors
* main()
* Destructors
* _default_exit() (default is infinite loop)
*/
extern "C" {
CH_IRQ_HANDLER(RTC_IRQHandler) {
CH_IRQ_PROLOGUE();
chSysLockFromIsr();
events_flag_isr(EVT_MASK_RTC_TICK);
chSysUnlockFromIsr();
rtc::interrupt::clear_all();
CH_IRQ_EPILOGUE();
}
}
static bool ui_dirty = true;
void ui::dirty_event() {
ui_dirty = true;
}
#include <string.h>
class EventDispatcher {
public:
@ -187,6 +97,26 @@ public:
};
}
void run() {
while(is_running) {
const auto events = wait();
dispatch(events);
}
}
void request_stop() {
is_running = false;
}
private:
touch::Manager touch_manager;
ui::Widget* const top_widget;
ui::Painter& painter;
ui::Context& context;
uint32_t encoder_last = 0;
bool is_running = true;
bool sd_card_present = false;
eventmask_t wait() {
return chEvtWaitAny(ALL_EVENTS);
}
@ -204,10 +134,6 @@ public:
handle_lcd_frame_sync();
}
if( events & EVT_MASK_SD_CARD_PRESENT ) {
handle_sd_card_detect();
}
if( events & EVT_MASK_SWITCHES ) {
handle_switches();
}
@ -221,121 +147,34 @@ public:
}
}
private:
touch::Manager touch_manager;
ui::Widget* const top_widget;
ui::Painter& painter;
ui::Context& context;
uint32_t encoder_last = 0;
void handle_application_queue() {
while( !shared_memory.application_queue.is_empty() ) {
auto message = shared_memory.application_queue.pop();
auto& fn = context.message_map[message->id];
if( fn ) {
fn(message);
}
message->state = Message::State::Free;
std::array<uint8_t, Message::MAX_SIZE> message_buffer;
while(Message* const message = shared_memory.application_queue.pop(message_buffer)) {
context.message_map().send(message);
}
}
void handle_rtc_tick() {
/*
if( shared_memory.application_queue.push(&rssi_request) ) {
led_rx.on();
}
*/
/*
if( callback_second_tick ) {
rtc::RTC datetime;
rtcGetTime(&RTCD1, &datetime);
const auto sd_card_present_now = sdc_lld_is_card_inserted(&SDCD1);
if( sd_card_present_now != sd_card_present ) {
sd_card_present = sd_card_present_now;
callback_second_tick(datetime);
}
*/
//static std::function<void(size_t app_n, size_t baseband_n)> callback_fifos_state;
//static std::function<void(systime_t ticks)> callback_cpu_ticks;
/*
if( callback_fifos_state ) {
callback_fifos_state(shared_memory.application_queue.len(), baseband_queue.len());
}
*/
/*
if( callback_cpu_ticks ) {
//const auto thread_self = chThdSelf();
const auto thread = chSysGetIdleThread();
//const auto ticks = chThdGetTicks(thread);
callback_cpu_ticks(thread->total_ticks);
}
*/
/*
callback_fifos_state = [&system_view](size_t app_n, size_t baseband_n) {
system_view.status_view.text_app_fifo_n.set(
ui::to_string_dec_uint(app_n, 3)
);
system_view.status_view.text_baseband_fifo_n.set(
ui::to_string_dec_uint(baseband_n, 3)
);
};
*/
/*
callback_cpu_ticks = [&system_view](systime_t ticks) {
static systime_t last_ticks = 0;
const auto delta_ticks = ticks - last_ticks;
last_ticks = ticks;
const auto text_pct = ui::to_string_dec_uint(delta_ticks / 2000000, 3) + "% idle";
system_view.status_view.text_ticks.set(
text_pct
);
};
*/
}
/*
void paint_widget(ui::Widget* const w) {
if( w->visible() ) {
if( w->dirty() ) {
w->paint(painter);
// Force-paint all children.
for(const auto child : w->children()) {
child->set_dirty();
paint_widget(child);
if( sd_card_present ) {
if( sdcConnect(&SDCD1) == CH_SUCCESS ) {
if( sd_card::filesystem::mount() == FR_OK ) {
SDCardStatusMessage message { true };
context.message_map().send(&message);
} else {
// TODO: Error, modal warning?
}
} else {
// TODO: Error, modal warning?
}
w->set_clean();
} else {
// Selectively paint all children.
for(const auto child : w->children()) {
paint_widget(child);
}
}
}
}
*/
void paint_widget(ui::Widget* const w) {
if( w->hidden() ) {
// Mark widget (and all children) as invisible.
w->visible(false);
} else {
// Mark this widget as visible and recurse.
w->visible(true);
sdcDisconnect(&SDCD1);
if( w->dirty() ) {
w->paint(painter);
// Force-paint all children.
for(const auto child : w->children()) {
child->set_dirty();
paint_widget(child);
}
w->set_clean();
} else {
// Selectively paint all children.
for(const auto child : w->children()) {
paint_widget(child);
}
SDCardStatusMessage message { false };
context.message_map().send(&message);
}
}
}
@ -385,14 +224,7 @@ private:
}
void handle_lcd_frame_sync() {
if( ui_dirty ) {
paint_widget(top_widget);
ui_dirty = false;
}
}
void handle_sd_card_detect() {
painter.paint_widget_tree(top_widget);
}
void handle_switches() {
@ -402,7 +234,7 @@ private:
if( switches_state[i] ) {
const auto event = static_cast<ui::KeyEvent>(i);
if( !event_bubble_key(event) ) {
context.focus_manager.update(top_widget, event);
context.focus_manager().update(top_widget, event);
}
}
}
@ -421,7 +253,7 @@ private:
}
bool event_bubble_key(const ui::KeyEvent event) {
auto target = context.focus_manager.focus_widget();
auto target = context.focus_manager().focus_widget();
while( (target != nullptr) && !target->on_key(event) ) {
target = target->parent();
}
@ -431,7 +263,7 @@ private:
}
void event_bubble_encoder(const ui::EncoderEvent event) {
auto target = context.focus_manager.focus_widget();
auto target = context.focus_manager().focus_widget();
while( (target != nullptr) && !target->on_encoder(event) ) {
target = target->parent();
}
@ -495,8 +327,6 @@ message_handlers[Message::ID::TestResults] = [&system_view](const Message* const
*/
int main(void) {
ui::Context context;
portapack::init();
if( !cpld_update_if_necessary() ) {
@ -506,51 +336,44 @@ int main(void) {
init_message_queues();
portapack::io.init();
portapack::display.init();
sdcStart(&SDCD1, nullptr);
rtc::interrupt::enable_second_inc();
nvicEnableVector(RTC_IRQn, CORTEX_PRIORITY_MASK(LPC_RTC_IRQ_PRIORITY));
controls_init();
lcd_frame_sync_configure();
events_initialize(chThdSelf());
events_initialize(chThdSelf());
init_message_queues();
ui::Context context;
ui::SystemView system_view {
context,
{ 0, 0, 240, 320 }
portapack::display.screen_rect()
};
ui::Painter painter;
context.message_map[Message::ID::FSKPacket] = [](const Message* const p) {
const auto message = static_cast<const FSKPacketMessage*>(p);
(void)message;
};
context.message_map[Message::ID::TXDone] = [](const Message* const p) {
const auto message = static_cast<const TXDoneMessage*>(p);
(void)message;
};
context.message_map[Message::ID::Retune] = [](const Message* const p) {
const auto message = static_cast<const RetuneMessage*>(p);
(void)message;
};
EventDispatcher event_dispatcher { &system_view, painter, context };
auto& message_handlers = context.message_map();
message_handlers.register_handler(Message::ID::Shutdown,
[&event_dispatcher](const Message* const) {
event_dispatcher.request_stop();
}
);
m4_init(portapack::spi_flash::baseband, portapack::memory::map::m4_code);
controls_init();
lcd_frame_sync_configure();
rtc_interrupt_enable();
m4txevent_interrupt_enable();
m4_init(portapack::spi_flash::baseband, portapack::spi_flash::m4_text_ram_base);
event_dispatcher.run();
while(true) {
const auto events = event_dispatcher.wait();
event_dispatcher.dispatch(events);
}
sdcDisconnect(&SDCD1);
sdcStop(&SDCD1);
portapack::shutdown();
m4_init(portapack::spi_flash::hackrf, portapack::memory::map::m4_code_hackrf);
rgu::reset(rgu::Reset::M0APP);
return 0;
}

View File

@ -21,6 +21,7 @@
#include "portapack.hpp"
#include "portapack_hal.hpp"
#include "portapack_persistent_memory.hpp"
#include "hackrf_hal.hpp"
#include "hackrf_gpio.hpp"
@ -131,6 +132,7 @@ void init() {
led_tx.setup();
clock_manager.init();
clock_manager.set_reference_ppb(persistent_memory::correction_ppb());
clock_manager.run_at_full_speed();
clock_manager.start_audio_pll();
@ -145,8 +147,6 @@ void init() {
}
void shutdown() {
sdcStop(&SDCD1);
display.shutdown();
radio::disable();
@ -157,6 +157,9 @@ void shutdown() {
// TODO: Wait a bit for supplies to discharge?
chSysDisable();
systick_stop();
hackrf::one::reset();
}

View File

@ -37,7 +37,6 @@
using namespace hackrf::one;
#include "portapack.hpp"
#include "portapack_persistent_memory.hpp"
namespace radio {
@ -118,9 +117,7 @@ void set_direction(const rf::Direction new_direction) {
}
bool set_tuning_frequency(const rf::Frequency frequency) {
const int32_t frequency_correction = frequency * portapack::persistent_memory::correction_ppb() / 1000000000;
rf::Frequency corrected_frequency = frequency + frequency_correction;
const auto tuning_config = tuning::config::create(corrected_frequency);
const auto tuning_config = tuning::config::create(frequency);
if( tuning_config.is_valid() ) {
first_if.disable();
@ -164,6 +161,10 @@ void streaming_enable() {
baseband_sgpio.streaming_enable();
}
void streaming_disable() {
baseband_sgpio.streaming_disable();
}
void disable() {
baseband_sgpio.streaming_disable();
baseband_codec.set_mode(max5864::Mode::Shutdown);

View File

@ -43,6 +43,7 @@ void set_baseband_filter_bandwidth(const uint32_t bandwidth_minimum);
void set_baseband_decimation_by(const size_t n);
void streaming_enable();
void streaming_disable();
void disable();
extern rffc507x::RFFC507x first_if;

View File

@ -49,7 +49,7 @@ int32_t ReceiverModel::reference_ppm_correction() const {
void ReceiverModel::set_reference_ppm_correction(int32_t v) {
persistent_memory::set_correction_ppb(v * 1000);
update_tuning_frequency();
clock_manager.set_reference_ppb(v * 1000);
}
bool ReceiverModel::rf_amp() const {
@ -92,19 +92,11 @@ uint32_t ReceiverModel::sampling_rate() const {
return baseband_configuration.sampling_rate;
}
void ReceiverModel::set_sampling_rate(uint32_t hz) {
baseband_configuration.sampling_rate = hz;
update_baseband_configuration();
}
uint32_t ReceiverModel::modulation() const {
return baseband_configuration.mode;
}
void ReceiverModel::set_modulation(int32_t v) {
baseband_configuration.mode = v;
update_modulation();
}
volume_t ReceiverModel::headphone_volume() const {
return headphone_volume_;
@ -120,10 +112,6 @@ uint32_t ReceiverModel::baseband_oversampling() const {
return baseband_configuration.decimation_factor;
}
void ReceiverModel::set_baseband_oversampling(uint32_t v) {
baseband_configuration.decimation_factor = v;
update_baseband_configuration();
}
void ReceiverModel::enable() {
radio::set_direction(rf::Direction::Receive);
@ -147,14 +135,17 @@ void ReceiverModel::disable() {
.decimation_factor = 1,
}
};
shared_memory.baseband_queue.push(&message);
while( !message.is_free() );
shared_memory.baseband_queue.push(message);
radio::disable();
}
int32_t ReceiverModel::tuning_offset() {
return -(sampling_rate() / 4);
if( baseband_configuration.mode == 4 ) {
return 0;
} else {
return -(sampling_rate() / 4);
}
}
void ReceiverModel::update_tuning_frequency() {
@ -177,24 +168,22 @@ void ReceiverModel::update_vga() {
radio::set_vga_gain(vga_gain_db_);
}
void ReceiverModel::update_modulation() {
void ReceiverModel::set_baseband_configuration(const BasebandConfiguration config) {
baseband_configuration = config;
update_baseband_configuration();
}
void ReceiverModel::update_baseband_configuration() {
radio::streaming_disable();
clock_manager.set_sampling_frequency(sampling_rate() * baseband_oversampling());
update_tuning_frequency();
radio::set_baseband_decimation_by(baseband_oversampling());
BasebandConfigurationMessage message { baseband_configuration };
shared_memory.baseband_queue.push(&message);
shared_memory.baseband_queue.push(message);
// Block until message is consumed, since we allocated it on the stack.
while( !message.is_free() );
if( baseband_configuration.mode == 3 ) {
update_fsk_configuration();
}
radio::streaming_enable();
}
void ReceiverModel::update_headphone_volume() {
@ -203,27 +192,3 @@ void ReceiverModel::update_headphone_volume() {
audio_codec.set_headphone_volume(headphone_volume_);
}
static constexpr FSKConfiguration fsk_configuration_ais = {
.symbol_rate = 9600,
.access_code = 0b01010101010101010101111110,
.access_code_length = 26,
.access_code_tolerance = 1,
.packet_length = 256,
};
static constexpr FSKConfiguration fsk_configuration_tpms_a = {
.symbol_rate = 19200,
.access_code = 0b0101010101010101010101010110,
.access_code_length = 28,
.access_code_tolerance = 1,
.packet_length = 160,
};
void ReceiverModel::update_fsk_configuration() {
FSKConfigurationMessage message { fsk_configuration_ais };
shared_memory.baseband_queue.push(&message);
// Block until message is consumed, since we allocated it on the stack.
while( !message.is_free() );
}

View File

@ -61,20 +61,19 @@ public:
void set_vga(int32_t v_db);
uint32_t sampling_rate() const;
void set_sampling_rate(uint32_t hz);
uint32_t modulation() const;
void set_modulation(int32_t v);
volume_t headphone_volume() const;
void set_headphone_volume(volume_t v);
uint32_t baseband_oversampling() const;
void set_baseband_oversampling(uint32_t v);
void enable();
void disable();
void set_baseband_configuration(const BasebandConfiguration config);
private:
rf::Frequency frequency_step_ { 25000 };
bool rf_amp_ { false };
@ -82,7 +81,7 @@ private:
uint32_t baseband_bandwidth_ { max2837::filter::bandwidth_minimum };
int32_t vga_gain_db_ { 32 };
BasebandConfiguration baseband_configuration {
.mode = 1,
.mode = 1, /* TODO: Enum! */
.sampling_rate = 3072000,
.decimation_factor = 4,
};
@ -96,11 +95,9 @@ private:
void update_lna();
void update_baseband_bandwidth();
void update_vga();
void update_modulation();
void update_baseband_configuration();
void update_headphone_volume();
void update_fsk_configuration();
};
#endif/*__RECEIVER_MODEL_H__*/

View File

@ -0,0 +1,47 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __SD_CARD_H__
#define __SD_CARD_H__
#include "ff.h"
namespace sd_card {
namespace filesystem {
namespace {
FATFS fs;
}
FRESULT mount() {
return f_mount(&fs, "", 0);
}
FRESULT unmount() {
return f_mount(NULL, "", 0);
}
} /* namespace filesystem */
} /* namespace sd_card */
#endif/*__SD_CARD_H__*/

View File

@ -38,7 +38,7 @@ using sample_t = uint16_t;
constexpr sample_t sample_max = 1023;
constexpr sample_t touch_threshold = sample_max * 0.3f;
constexpr sample_t touch_threshold = sample_max * 0.5f;
struct Samples {
sample_t xp;

View File

@ -119,8 +119,7 @@ void TransmitterModel::disable() {
.decimation_factor = 1,
}
};
shared_memory.baseband_queue.push(&message);
while( !message.is_free() );
shared_memory.baseband_queue.push(message);
radio::disable();
}
@ -154,13 +153,14 @@ void TransmitterModel::update_modulation() {
}
void TransmitterModel::update_baseband_configuration() {
radio::streaming_disable();
clock_manager.set_sampling_frequency(sampling_rate() * baseband_oversampling());
update_tuning_frequency();
radio::set_baseband_decimation_by(baseband_oversampling());
BasebandConfigurationMessage message { baseband_configuration };
shared_memory.baseband_queue.push(&message);
shared_memory.baseband_queue.push(message);
// Block until message is consumed, since we allocated it on the stack.
while( !message.is_free() );
radio::streaming_enable();
}

View File

@ -72,7 +72,7 @@ private:
uint32_t baseband_bandwidth_ { max2837::filter::bandwidth_minimum };
int32_t vga_gain_db_ { 8 };
BasebandConfiguration baseband_configuration {
.mode = 15,
.mode = 16,
.sampling_rate = 2280000,
.decimation_factor = 1,
};

View File

@ -52,7 +52,7 @@ void AFSKSetupView::paint(Painter& painter) {
void AFSKSetupView::updfreq(rf::Frequency f) {
char finalstr[9] = {0};
persistent_memory::set_tuned_frequency(f);
portapack::persistent_memory::set_tuned_frequency(f);
transmitter_model.set_tuning_frequency(f);
auto mhz = to_string_dec_int(f / 1000000, 3);
@ -90,16 +90,16 @@ AFSKSetupView::AFSKSetupView(
&button_done
} });
if (persistent_memory::afsk_config() & 1) checkbox_lsb.set_value(true);
if (persistent_memory::afsk_config() & 2) checkbox_parity.set_value(true);
if (persistent_memory::afsk_config() & 4) checkbox_datasize.set_value(true);
if (portapack::persistent_memory::afsk_config() & 1) checkbox_lsb.set_value(true);
if (portapack::persistent_memory::afsk_config() & 2) checkbox_parity.set_value(true);
if (portapack::persistent_memory::afsk_config() & 4) checkbox_datasize.set_value(true);
updfreq(persistent_memory::tuned_frequency());
updfreq(portapack::persistent_memory::tuned_frequency());
field_mark.set_value(persistent_memory::afsk_mark_freq()*100);
field_space.set_value(persistent_memory::afsk_space_freq()*100);
field_bw.set_value(persistent_memory::afsk_bw());
rpt = (persistent_memory::afsk_config() >> 8) & 0xFF;
field_mark.set_value(portapack::persistent_memory::afsk_mark_freq()*100);
field_space.set_value(portapack::persistent_memory::afsk_space_freq()*100);
field_bw.set_value(portapack::persistent_memory::afsk_bw());
rpt = (portapack::persistent_memory::afsk_config() >> 8) & 0xFF;
if (rpt > 99) rpt = 5;
field_repeat.set_value(rpt);
@ -111,18 +111,18 @@ AFSKSetupView::AFSKSetupView(
nav.push(new_view);
};
if (persistent_memory::afsk_bitrate() == 1200) {
if (portapack::persistent_memory::afsk_bitrate() == 1200) {
button_setbps.set_text("1200 bps");
} else {
button_setbps.set_text("2400 bps");
}
button_setbps.on_select = [this](Button&){
if (persistent_memory::afsk_bitrate() == 1200) {
persistent_memory::set_afsk_bitrate(2400);
if (portapack::persistent_memory::afsk_bitrate() == 1200) {
portapack::persistent_memory::set_afsk_bitrate(2400);
button_setbps.set_text("2400 bps");
} else {
persistent_memory::set_afsk_bitrate(1200);
portapack::persistent_memory::set_afsk_bitrate(1200);
button_setbps.set_text("1200 bps");
}
};
@ -130,15 +130,15 @@ AFSKSetupView::AFSKSetupView(
button_done.on_select = [this,&nav](Button&){
uint32_t afsk_config = 0;
persistent_memory::set_afsk_mark(field_mark.value()/100);
persistent_memory::set_afsk_space(field_space.value()/100);
persistent_memory::set_afsk_bw(field_bw.value());
portapack::persistent_memory::set_afsk_mark(field_mark.value()/100);
portapack::persistent_memory::set_afsk_space(field_space.value()/100);
portapack::persistent_memory::set_afsk_bw(field_bw.value());
if (checkbox_lsb.value() == true) afsk_config |= 1;
if (checkbox_parity.value() == true) afsk_config |= 2;
if (checkbox_datasize.value() == true) afsk_config |= 4;
afsk_config |= (field_repeat.value() << 8);
persistent_memory::set_afsk_config(afsk_config);
portapack::persistent_memory::set_afsk_config(afsk_config);
nav.pop();
};

View File

@ -26,13 +26,15 @@
namespace ui {
void Audio::on_show() {
context().message_map[Message::ID::AudioStatistics] = [this](const Message* const p) {
this->on_statistics_update(static_cast<const AudioStatisticsMessage*>(p)->statistics);
};
context().message_map().register_handler(Message::ID::AudioStatistics,
[this](const Message* const p) {
this->on_statistics_update(static_cast<const AudioStatisticsMessage*>(p)->statistics);
}
);
}
void Audio::on_hide() {
context().message_map[Message::ID::AudioStatistics] = nullptr;
context().message_map().unregister_handler(Message::ID::AudioStatistics);
}
void Audio::paint(Painter& painter) {

View File

@ -0,0 +1,73 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "ui_baseband_stats_view.hpp"
#include <string>
#include <algorithm>
#include "hackrf_hal.hpp"
using namespace hackrf::one;
namespace ui {
/* BasebandStatsView *****************************************************/
BasebandStatsView::BasebandStatsView() {
add_children({ {
&text_stats,
} });
}
void BasebandStatsView::on_show() {
context().message_map().register_handler(Message::ID::BasebandStatistics,
[this](const Message* const p) {
this->on_statistics_update(static_cast<const BasebandStatisticsMessage*>(p)->statistics);
}
);
}
void BasebandStatsView::on_hide() {
context().message_map().unregister_handler(Message::ID::BasebandStatistics);
}
static std::string ticks_to_percent_string(const uint32_t ticks) {
constexpr size_t decimal_digits = 1;
constexpr size_t decimal_factor = decimal_digits * 10;
const uint32_t percent_x10 = ticks / (base_m4_clk_f / (100 * decimal_factor));
const uint32_t percent_x10_clipped = std::min(percent_x10, static_cast<uint32_t>(100 * decimal_factor) - 1);
return
to_string_dec_uint(percent_x10_clipped / decimal_factor, 2) + "." +
to_string_dec_uint(percent_x10_clipped % decimal_factor, decimal_digits, '0');
}
void BasebandStatsView::on_statistics_update(const BasebandStatistics& statistics) {
std::string message = ticks_to_percent_string(statistics.idle_ticks)
+ " " + ticks_to_percent_string(statistics.main_ticks)
+ " " + ticks_to_percent_string(statistics.rssi_ticks)
+ " " + ticks_to_percent_string(statistics.baseband_ticks);
text_stats.set(message);
}
} /* namespace ui */

View File

@ -0,0 +1,48 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __UI_BASEBAND_STATS_VIEW_H__
#define __UI_BASEBAND_STATS_VIEW_H__
#include "ui_widget.hpp"
#include "message.hpp"
namespace ui {
class BasebandStatsView : public View {
public:
BasebandStatsView();
void on_show() override;
void on_hide() override;
private:
Text text_stats {
{ 0 * 8, 0, (4 * 4 + 3) * 8, 1 * 16 },
"",
};
void on_statistics_update(const BasebandStatistics& statistics);
};
} /* namespace ui */
#endif/*__UI_BASEBAND_STATS_VIEW_H__*/

View File

@ -26,13 +26,15 @@
namespace ui {
void Channel::on_show() {
context().message_map[Message::ID::ChannelStatistics] = [this](const Message* const p) {
this->on_statistics_update(static_cast<const ChannelStatisticsMessage*>(p)->statistics);
};
context().message_map().register_handler(Message::ID::ChannelStatistics,
[this](const Message* const p) {
this->on_statistics_update(static_cast<const ChannelStatisticsMessage*>(p)->statistics);
}
);
}
void Channel::on_hide() {
context().message_map[Message::ID::ChannelStatistics] = nullptr;
context().message_map().unregister_handler(Message::ID::ChannelStatistics);
}
void Channel::paint(Painter& painter) {

View File

@ -26,8 +26,32 @@ using namespace portapack;
namespace ui {
void Console::clear() {
display.fill_rectangle(
screen_rect(),
Color::black()
);
pos = { 0, 0 };
display.scroll_set_position(0);
}
void Console::write(const std::string message) {
(void)message;
const Style& s = style();
const Font& font = s.font;
const auto rect = screen_rect();
for(const auto c : message) {
const auto glyph = font.glyph(c);
const auto advance = glyph.advance();
if( (pos.x + advance.x) > rect.width() ) {
crlf();
}
const Point pos_glyph {
static_cast<Coord>(rect.pos.x + pos.x),
display.scroll_area_y(pos.y)
};
display.draw_glyph(pos_glyph, glyph, s.foreground, s.background);
pos.x += advance.x;
}
}
void Console::writeln(const std::string message) {
@ -36,33 +60,37 @@ void Console::writeln(const std::string message) {
}
void Console::paint(Painter& painter) {
// Do nothing.
(void)painter;
/*
if( visible() ) {
const auto r = screen_rect();
display.scroll_set_area(r.top(), r.bottom());
display.scroll_set_position(0);
painter.fill_rectangle(
r,
background
);
} else {
display.scroll_disable();
}
*/
}
void Console::on_show() {
const auto screen_r = screen_rect();
display.scroll_set_area(screen_r.top(), screen_r.bottom());
clear();
}
void Console::on_hide() {
/* TODO: Clear region to eliminate brief flash of content at un-shifted
* position?
*/
display.scroll_disable();
}
void Console::crlf() {
const auto line_height = style().font.line_height();
const Style& s = style();
const auto sr = screen_rect();
const auto line_height = s.font.line_height();
pos.x = 0;
pos.y += line_height;
const int32_t y_excess = pos.y + line_height - size().h;
const int32_t y_excess = pos.y + line_height - sr.height();
if( y_excess > 0 ) {
display.scroll(-line_height);
display.scroll(-y_excess);
pos.y -= y_excess;
const Rect dirty { 0, display.scroll_area_y(pos.y), size().w, line_height };
display.fill_rectangle(dirty, background);
const Rect dirty { sr.left(), display.scroll_area_y(pos.y), sr.width(), line_height };
display.fill_rectangle(dirty, s.background);
}
}

View File

@ -32,21 +32,16 @@ namespace ui {
class Console : public Widget {
public:
constexpr Console(
const Rect parent_rect
) : Widget { parent_rect }
{
}
void clear();
void write(const std::string message);
void writeln(const std::string message);
void paint(Painter& painter) override;
void on_show() override;
void on_hide() override;
private:
static constexpr Color background { Color::black() };
static constexpr Color foreground { Color::white() };
Point pos { 0, 0 };
void crlf();

View File

@ -31,45 +31,10 @@
#include "radio.hpp"
#include "hackrf_hal.hpp"
using namespace hackrf::one;
namespace ui {
FRESULT fr; /* FatFs function common result code */
/* BasebandStatsView *****************************************************/
BasebandStatsView::BasebandStatsView() {
add_children({ {
&text_used,
&text_idle,
} });
}
void BasebandStatsView::on_show() {
context().message_map[Message::ID::BasebandStatistics] = [this](const Message* const p) {
this->on_statistics_update(static_cast<const BasebandStatisticsMessage*>(p)->statistics);
};
}
void BasebandStatsView::on_hide() {
context().message_map[Message::ID::BasebandStatistics] = nullptr;
}
static std::string ticks_to_percent_string(const uint32_t ticks) {
const uint32_t percent_x100 = ticks / (base_m4_clk_f / 10000);
return
to_string_dec_uint(percent_x100 / 100, 3) + "." +
to_string_dec_uint(percent_x100 % 100, 2, '0') + "%";
}
void BasebandStatsView::on_statistics_update(const BasebandStatistics& statistics) {
text_used.set(ticks_to_percent_string(statistics.baseband_ticks));
text_idle.set(ticks_to_percent_string(statistics.idle_ticks));
}
DebugMemoryView::DebugMemoryView(NavigationView& nav) {
add_children({ {
&text_title,
@ -195,7 +160,7 @@ DebugSDView::DebugSDView(NavigationView& nav) {
fr = f_open(&fdst, "TST.SND", FA_OPEN_EXISTING | FA_READ);
if (!fr) led_rx.on();
//if (!fr) led_rx.on();
/*fr = f_read(&fdst, buffer, 512*2, &bw);

View File

@ -34,27 +34,6 @@ namespace ui {
char hexify(char in);
class BasebandStatsView : public View {
public:
BasebandStatsView();
void on_show() override;
void on_hide() override;
private:
Text text_used {
{ 0, 0, 7 * 8, 1 * 16 },
"",
};
Text text_idle {
{ 8 * 8, 0, 7 * 8, 1 * 16 },
"",
};
void on_statistics_update(const BasebandStatistics& statistics);
};
class DebugMemoryView : public View {
public:
DebugMemoryView(NavigationView& nav);

View File

@ -232,13 +232,16 @@ JammerView::JammerView(
button_transmit.on_select = [this,&transmitter_model](Button&) {
uint8_t i = 0;
rf::Frequency t, range_lower;
auto& message_map = context().message_map();
context().message_map[Message::ID::Retune] = [this, &transmitter_model](const Message* const p) {
const auto message = static_cast<const RetuneMessage*>(p);
if (message->freq > 0) {
transmitter_model.set_tuning_frequency(message->freq);
message_map.register_handler(Message::ID::Retune,
[this,&transmitter_model](Message* const p) {
const auto message = static_cast<const RetuneMessage*>(p);
if (message->freq > 0) {
transmitter_model.set_tuning_frequency(message->freq);
}
}
};
);
for (i = 0; i < 16; i++) {
shared_memory.jammer_ranges[i].active = false;

View File

@ -188,7 +188,7 @@ LCRView::LCRView(
};
transmitter_model.set_modulation(16);
transmitter_model.set_tuning_frequency(persistent_memory::tuned_frequency());
transmitter_model.set_tuning_frequency(portapack::persistent_memory::tuned_frequency());
memset(litteral, 0, 5*8);
memset(rgsb, 0, 5);
@ -222,8 +222,8 @@ LCRView::LCRView(
checkbox_am_e.set_value(true);
// Recap: tx freq @ bps
auto fstr = to_string_dec_int(persistent_memory::tuned_frequency() / 1000, 6);
auto bstr = to_string_dec_int(persistent_memory::afsk_bitrate(), 4);
auto fstr = to_string_dec_int(portapack::persistent_memory::tuned_frequency() / 1000, 6);
auto bstr = to_string_dec_int(portapack::persistent_memory::afsk_bitrate(), 4);
strcat(finalstr, fstr.c_str());
strcat(finalstr, " @ ");
@ -277,31 +277,35 @@ LCRView::LCRView(
button_transmit.on_select = [this,&transmitter_model](Button&){
uint16_t c;
auto& message_map = context().message_map();
make_frame();
shared_memory.afsk_samples_per_bit = 228000/persistent_memory::afsk_bitrate();
shared_memory.afsk_phase_inc_mark = persistent_memory::afsk_mark_freq()*(65536*1024)/2280;
shared_memory.afsk_phase_inc_space = persistent_memory::afsk_space_freq()*(65536*1024)/2280;
shared_memory.afsk_samples_per_bit = 228000/portapack::persistent_memory::afsk_bitrate();
shared_memory.afsk_phase_inc_mark = portapack::persistent_memory::afsk_mark_freq()*(65536*1024)/2280;
shared_memory.afsk_phase_inc_space = portapack::persistent_memory::afsk_space_freq()*(65536*1024)/2280;
shared_memory.afsk_fmmod = persistent_memory::afsk_bw()*33; // ?
shared_memory.afsk_fmmod = portapack::persistent_memory::afsk_bw()*33;
memset(shared_memory.lcrdata, 0, 256);
memcpy(shared_memory.lcrdata, lcrframe_f, 256);
shared_memory.afsk_transmit_done = false;
shared_memory.afsk_repeat = ((persistent_memory::afsk_config() >> 8) & 0xFF);
shared_memory.afsk_repeat = ((portapack::persistent_memory::afsk_config() >> 8) & 0xFF);
context().message_map[Message::ID::TXDone] = [this, &transmitter_model](const Message* const p) {
const auto message = static_cast<const TXDoneMessage*>(p);
if (message->n > 0) {
char str[8] = "0... ";
str[0] = hexify(message->n);
text_status.set(str);
} else {
text_status.set("Done ! ");
transmitter_model.disable();
message_map.register_handler(Message::ID::TXDone,
[this,&transmitter_model](Message* const p) {
const auto message = static_cast<const TXDoneMessage*>(p);
if (message->n > 0) {
char str[8] = "0... ";
str[0] = hexify(message->n);
text_status.set(str);
} else {
text_status.set("Done ! ");
transmitter_model.disable();
}
}
};
);
text_status.set("0... ");

View File

@ -21,6 +21,7 @@
#include "ui_navigation.hpp"
#include "portapack.hpp"
#include "receiver_model.hpp"
#include "transmitter_model.hpp"
#include "portapack_persistent_memory.hpp"
@ -265,16 +266,8 @@ PlayDeadView::PlayDeadView(NavigationView& nav, bool booting) {
HackRFFirmwareView::HackRFFirmwareView(NavigationView& nav) {
button_yes.on_select = [&nav](Button&){
shutdown();
m4_init(spi_flash::hackrf, reinterpret_cast<void*>(0x10000000));
while(true) {
__WFE();
}
m4_request_shutdown();
};
//377.6M: bouts de musique
button_no.on_select = [&nav](Button&){
nav.pop();
@ -282,6 +275,10 @@ HackRFFirmwareView::HackRFFirmwareView(NavigationView& nav) {
add_children({ {
&text_title,
&text_description_1,
&text_description_2,
&text_description_3,
&text_description_4,
&button_yes,
&button_no,
} });

View File

@ -135,8 +135,28 @@ public:
private:
Text text_title {
{ 6 * 8, 7 * 16, 19 * 8, 16 },
"Enter HackRF Mode?"
{ 76, 4 * 16, 19 * 8, 16 },
"HackRF Mode"
};
Text text_description_1 {
{ 4, 7 * 16, 19 * 8, 16 },
"Run stock HackRF firmware and"
};
Text text_description_2 {
{ 12, 8 * 16, 19 * 8, 16 },
"disable PortaPack until the"
};
Text text_description_3 {
{ 4, 9 * 16, 19 * 8, 16 },
"unit is reset or disconnected"
};
Text text_description_4 {
{ 76, 10 * 16, 19 * 8, 16 },
"from power?"
};
Button button_yes {

View File

@ -21,9 +21,16 @@
#include "ui_receiver.hpp"
#include "ui_spectrum.hpp"
#include "ui_console.hpp"
#include "portapack.hpp"
using namespace portapack;
#include "ais_baseband.hpp"
#include "ff.h"
namespace ui {
/* BasebandBandwidthField ************************************************/
@ -269,7 +276,7 @@ void FrequencyKeypadView::field_toggle() {
void FrequencyKeypadView::update_text() {
const auto s = mhz.as_string() + "." + submhz.as_string();
text_value.set(s.c_str());
text_value.set(s);
}
/* FrequencyOptionsView **************************************************/
@ -402,7 +409,6 @@ ReceiverView::ReceiverView(
&field_volume,
&view_frequency_options,
&view_rf_gain_options,
&waterfall,
} });
button_done.on_select = [&nav](Button&){
@ -483,6 +489,7 @@ ReceiverView::ReceiverView(
}
ReceiverView::~ReceiverView() {
// TODO: Manipulating audio codec here, and in ui_receiver.cpp. Good to do
// both?
audio_codec.headphone_mute();
@ -490,13 +497,107 @@ ReceiverView::~ReceiverView() {
receiver_model.disable();
}
void ReceiverView::set_parent_rect(const Rect new_parent_rect) {
const ui::Dim header_height = 3 * 16;
void ReceiverView::on_show() {
auto& message_map = context().message_map();
message_map.register_handler(Message::ID::AISPacket,
[this](Message* const p) {
const auto message = static_cast<const AISPacketMessage*>(p);
this->on_packet_ais(*message);
}
);
message_map.register_handler(Message::ID::TPMSPacket,
[this](Message* const p) {
const auto message = static_cast<const TPMSPacketMessage*>(p);
this->on_packet_tpms(*message);
}
);
message_map.register_handler(Message::ID::SDCardStatus,
[this](Message* const p) {
const auto message = static_cast<const SDCardStatusMessage*>(p);
this->on_sd_card_mounted(message->is_mounted);
}
);
}
waterfall.set_parent_rect({
0, header_height,
new_parent_rect.width(), static_cast<ui::Dim>(new_parent_rect.height() - header_height)
});
void ReceiverView::on_hide() {
auto& message_map = context().message_map();
message_map.unregister_handler(Message::ID::SDCardStatus);
message_map.unregister_handler(Message::ID::TPMSPacket);
message_map.unregister_handler(Message::ID::AISPacket);
}
void ReceiverView::on_packet_ais(const AISPacketMessage& message) {
const auto result = baseband::ais::packet_decode(message.packet.payload, message.packet.bits_received);
auto console = reinterpret_cast<Console*>(widget_content.get());
if( result.first == "OK" ) {
console->writeln(result.second);
}
}
static FIL fil_tpms;
void ReceiverView::on_packet_tpms(const TPMSPacketMessage& message) {
auto payload = message.packet.payload;
auto payload_length = message.packet.bits_received;
std::string hex_data;
std::string hex_error;
uint8_t byte_data = 0;
uint8_t byte_error = 0;
for(size_t i=0; i<payload_length; i+=2) {
const auto bit_data = payload[i+1];
const auto bit_error = (payload[i+0] == payload[i+1]);
byte_data <<= 1;
byte_data |= bit_data ? 1 : 0;
byte_error <<= 1;
byte_error |= bit_error ? 1 : 0;
if( ((i >> 1) & 7) == 7 ) {
hex_data += to_string_hex(byte_data, 2);
hex_error += to_string_hex(byte_error, 2);
}
}
auto console = reinterpret_cast<Console*>(widget_content.get());
console->writeln(hex_data.substr(0, 240 / 8));
if( !f_error(&fil_tpms) ) {
rtc::RTC datetime;
rtcGetTime(&RTCD1, &datetime);
std::string timestamp =
to_string_dec_uint(datetime.year(), 4) +
to_string_dec_uint(datetime.month(), 2, '0') +
to_string_dec_uint(datetime.day(), 2, '0') +
to_string_dec_uint(datetime.hour(), 2, '0') +
to_string_dec_uint(datetime.minute(), 2, '0') +
to_string_dec_uint(datetime.second(), 2, '0');
const auto tuning_frequency = receiver_model.tuning_frequency();
// TODO: function doesn't take uint64_t, so when >= 1<<32, weirdness will ensue!
const auto tuning_frequency_str = to_string_dec_uint(tuning_frequency, 10);
std::string log = timestamp + " " + tuning_frequency_str + " FSK 38.4 19.2 " + hex_data + "/" + hex_error + "\r\n";
f_puts(log.c_str(), &fil_tpms);
f_sync(&fil_tpms);
}
}
void ReceiverView::on_sd_card_mounted(const bool is_mounted) {
if( is_mounted ) {
const auto open_result = f_open(&fil_tpms, "tpms.txt", FA_WRITE | FA_OPEN_ALWAYS);
if( open_result == FR_OK ) {
const auto fil_size = f_size(&fil_tpms);
const auto seek_result = f_lseek(&fil_tpms, fil_size);
if( seek_result != FR_OK ) {
f_close(&fil_tpms);
}
} else {
// TODO: Error, indicate somehow.
}
}
}
void ReceiverView::focus() {
@ -524,13 +625,58 @@ void ReceiverView::on_vga_changed(int32_t v_db) {
}
void ReceiverView::on_modulation_changed(int32_t modulation) {
if( modulation == 4 ) {
/* TODO: This is TERRIBLE!!! */
receiver_model.set_sampling_rate(2457600);
} else {
receiver_model.set_sampling_rate(3072000);
/* TODO: This is TERRIBLE!!! */
switch(modulation) {
case 3:
case 5:
receiver_model.set_baseband_configuration({
.mode = modulation,
.sampling_rate = 2457600,
.decimation_factor = 4,
});
receiver_model.set_baseband_bandwidth(1750000);
break;
case 4:
receiver_model.set_baseband_configuration({
.mode = modulation,
.sampling_rate = 20000000,
.decimation_factor = 1,
});
receiver_model.set_baseband_bandwidth(12000000);
break;
default:
receiver_model.set_baseband_configuration({
.mode = modulation,
.sampling_rate = 3072000,
.decimation_factor = 4,
});
receiver_model.set_baseband_bandwidth(1750000);
break;
}
remove_child(widget_content.get());
widget_content.reset();
switch(modulation) {
case 3:
case 5:
widget_content = std::make_unique<Console>();
add_child(widget_content.get());
break;
default:
widget_content = std::make_unique<spectrum::WaterfallWidget>();
add_child(widget_content.get());
break;
}
if( widget_content ) {
const ui::Dim header_height = 3 * 16;
const ui::Rect rect { 0, header_height, parent_rect.width(), static_cast<ui::Dim>(parent_rect.height() - header_height) };
widget_content->set_parent_rect(rect);
}
receiver_model.set_modulation(modulation);
}
void ReceiverView::on_show_options_frequency() {

View File

@ -27,7 +27,6 @@
#include "ui_navigation.hpp"
#include "ui_painter.hpp"
#include "ui_widget.hpp"
#include "ui_spectrum.hpp"
#include "utility.hpp"
@ -363,10 +362,11 @@ public:
ReceiverView(NavigationView& nav, ReceiverModel& receiver_model);
~ReceiverView();
void set_parent_rect(const Rect new_parent_rect) override;
void focus() override;
void on_show() override;
void on_hide() override;
private:
ReceiverModel& receiver_model;
@ -383,12 +383,12 @@ private:
};
Button button_done {
{ 0 * 8, 1 * 16, 3 * 8, 16 },
{ 0 * 8, 0 * 16, 3 * 8, 16 },
" < ",
};
FrequencyField field_frequency {
{ 3 * 8, 1 * 16 },
{ 0 * 8, 1 * 16 },
};
LNAGainField field_lna {
@ -415,7 +415,9 @@ private:
{ " AM ", 0 },
{ "NFM ", 1 },
{ "WFM ", 2 },
{ "FSK ", 3 },
{ "AIS ", 3 },
{ "TPMS", 5 },
{ "SPEC", 4 },
}
};
/*
@ -455,7 +457,7 @@ private:
&style_options_group
};
spectrum::WaterfallWidget waterfall;
std::unique_ptr<Widget> widget_content;
void on_tuning_frequency_changed(rf::Frequency f);
void on_baseband_bandwidth_changed(uint32_t bandwidth_hz);
@ -470,6 +472,10 @@ private:
void on_headphone_volume_changed(int32_t v);
// void on_baseband_oversampling_changed(int32_t v);
void on_edit_frequency();
void on_packet_ais(const AISPacketMessage& message);
void on_packet_tpms(const TPMSPacketMessage& message);
void on_sd_card_mounted(const bool is_mounted);
};
} /* namespace ui */

View File

@ -26,13 +26,15 @@
namespace ui {
void RSSI::on_show() {
context().message_map[Message::ID::RSSIStatistics] = [this](const Message* const p) {
this->on_statistics_update(static_cast<const RSSIStatisticsMessage*>(p)->statistics);
};
context().message_map().register_handler(Message::ID::RSSIStatistics,
[this](const Message* const p) {
this->on_statistics_update(static_cast<const RSSIStatisticsMessage*>(p)->statistics);
}
);
}
void RSSI::on_hide() {
context().message_map[Message::ID::RSSIStatistics] = nullptr;
context().message_map().unregister_handler(Message::ID::RSSIStatistics);
}
void RSSI::paint(Painter& painter) {

View File

@ -127,7 +127,7 @@ SetFrequencyCorrectionView::SetFrequencyCorrectionView(
} });
SetFrequencyCorrectionModel model {
portapack::persistent_memory::correction_ppb() / 1000
static_cast<int8_t>(portapack::persistent_memory::correction_ppb() / 1000)
};
form_init(model);

View File

@ -25,7 +25,6 @@
#include "ui_widget.hpp"
#include "ui_menu.hpp"
#include "ui_navigation.hpp"
#include "portapack_persistent_memory.hpp"
#include <cstdint>
@ -191,7 +190,7 @@ private:
Text text_firmware {
{ 0, 128, 240, 16 },
"Firmware Version HAVOC 0.10",
"Git Commit Hash " GIT_REVISION,
};
Text text_cpld_hackrf {

View File

@ -40,6 +40,10 @@ namespace spectrum {
class FrequencyScale : public Widget {
public:
void on_show() override {
clear();
}
void set_spectrum_sampling_rate(const uint32_t new_sampling_rate, const size_t new_spectrum_bins) {
if( (spectrum_sampling_rate != new_sampling_rate) ||
(spectrum_bins != new_spectrum_bins) ) {
@ -83,6 +87,12 @@ private:
uint32_t channel_filter_pass_frequency { 0 };
uint32_t channel_filter_stop_frequency { 0 };
void clear() {
spectrum_sampling_rate = 0;
spectrum_bins = 0;
set_dirty();
}
void clear_background(Painter& painter, const Rect r) {
painter.fill_rectangle(r, Color::black());
}
@ -181,6 +191,8 @@ private:
class WaterfallView : public Widget {
public:
void on_show() override {
clear();
const auto screen_r = screen_rect();
display.scroll_set_area(screen_r.top(), screen_r.bottom());
}
@ -201,16 +213,15 @@ public:
const ChannelSpectrum& spectrum
) {
/* TODO: static_assert that message.spectrum.db.size() >= pixel_row.size() */
const auto& db = *spectrum.db;
std::array<Color, 240> pixel_row;
for(size_t i=0; i<120; i++) {
const auto pixel_color = spectrum_rgb3_lut[db[256 - 120 + i]];
const auto pixel_color = spectrum_rgb3_lut[spectrum.db[256 - 120 + i]];
pixel_row[i] = pixel_color;
}
for(size_t i=120; i<240; i++) {
const auto pixel_color = spectrum_rgb3_lut[db[i - 120]];
const auto pixel_color = spectrum_rgb3_lut[spectrum.db[i - 120]];
pixel_row[i] = pixel_color;
}
@ -221,6 +232,14 @@ public:
pixel_row
);
}
private:
void clear() {
display.fill_rectangle(
screen_rect(),
Color::black()
);
}
};
class WaterfallWidget : public View {
@ -233,13 +252,15 @@ public:
}
void on_show() override {
context().message_map[Message::ID::ChannelSpectrum] = [this](const Message* const p) {
this->on_channel_spectrum(reinterpret_cast<const ChannelSpectrumMessage*>(p)->spectrum);
};
context().message_map().register_handler(Message::ID::ChannelSpectrum,
[this](const Message* const p) {
this->on_channel_spectrum(reinterpret_cast<const ChannelSpectrumMessage*>(p)->spectrum);
}
);
}
void on_hide() override {
context().message_map[Message::ID::ChannelSpectrum] = nullptr;
context().message_map().unregister_handler(Message::ID::ChannelSpectrum);
}
void set_parent_rect(const Rect new_parent_rect) override {

View File

@ -73,7 +73,7 @@ WhistleView::WhistleView(
chMBInit(&mbox, mbox_buffer, 3);
transmitter_model.set_modulation(17);
transmitter_model.set_tuning_frequency(persistent_memory::tuned_frequency());
transmitter_model.set_tuning_frequency(portapack::persistent_memory::tuned_frequency());
add_children({ {
&button_transmit,

View File

@ -125,13 +125,23 @@ CSRC = $(PORTSRC) \
CPPSRC = main.cpp \
message_queue.cpp \
event_m4.cpp \
irq_ipc_m4.cpp \
gpdma.cpp \
baseband_dma.cpp \
portapack_shared_memory.cpp \
baseband_processor.cpp \
channel_decimator.cpp \
dsp_decimate.cpp \
dsp_demodulate.cpp \
matched_filter.cpp \
proc_am_audio.cpp \
proc_nfm_audio.cpp \
proc_wfm_audio.cpp \
proc_ais.cpp \
proc_wideband_spectrum.cpp \
proc_tpms.cpp \
dsp_squelch.cpp \
clock_recovery.cpp \
access_code_correlator.cpp \
packet_builder.cpp \
dsp_fft.cpp \
dsp_fir_taps.cpp \
@ -142,6 +152,7 @@ CPPSRC = main.cpp \
audio_dma.cpp \
touch_dma.cpp \
../common/utility.cpp \
../common/chibios_cpp.cpp \
../common/debug.cpp \
../common/gcc.cpp
@ -222,7 +233,8 @@ CPPWARN = -Wall -Wextra
# TODO: Switch -DCRT0_INIT_DATA depending on load from RAM or SPIFI?
# NOTE: _RANDOM_TCC to kill a GCC 4.9.3 error with std::max argument types
DDEFS = -DLPC43XX -DLPC43XX_M4 -D__NEWLIB__ -DHACKRF_ONE \
-DTOOLCHAIN_GCC -DTOOLCHAIN_GCC_ARM -D_RANDOM_TCC=0
-DTOOLCHAIN_GCC -DTOOLCHAIN_GCC_ARM -D_RANDOM_TCC=0 \
-DGIT_REVISION=\"$(GIT_REVISION)\"
# List all default ASM defines here, like -D_DEBUG=1
DADEFS =

View File

@ -0,0 +1,122 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "baseband_processor.hpp"
#include "portapack_shared_memory.hpp"
#include "dsp_fft.hpp"
#include "audio_dma.hpp"
#include "message.hpp"
#include "event_m4.hpp"
#include "utility.hpp"
#include <cstddef>
#include <algorithm>
void BasebandProcessor::update_spectrum() {
// Called from idle thread (after EVT_MASK_SPECTRUM is flagged)
if( channel_spectrum_request_update ) {
/* Decimated buffer is full. Compute spectrum. */
channel_spectrum_request_update = false;
fft_c_preswapped(channel_spectrum);
ChannelSpectrumMessage spectrum_message;
for(size_t i=0; i<spectrum_message.spectrum.db.size(); i++) {
const auto mag2 = magnitude_squared(channel_spectrum[i]);
const float db = complex16_mag_squared_to_dbv_norm(mag2);
constexpr float mag_scale = 5.0f;
const unsigned int v = (db * mag_scale) + 255.0f;
spectrum_message.spectrum.db[i] = std::max(0U, std::min(255U, v));
}
/* TODO: Rename .db -> .magnitude, or something more (less!) accurate. */
spectrum_message.spectrum.db_count = spectrum_message.spectrum.db.size();
spectrum_message.spectrum.sampling_rate = channel_spectrum_sampling_rate;
spectrum_message.spectrum.channel_filter_pass_frequency = channel_filter_pass_frequency;
spectrum_message.spectrum.channel_filter_stop_frequency = channel_filter_stop_frequency;
shared_memory.application_queue.push(spectrum_message);
}
}
void BasebandProcessor::feed_channel_stats(const buffer_c16_t channel) {
channel_stats.feed(
channel,
[this](const ChannelStatistics statistics) {
this->post_channel_stats_message(statistics);
}
);
}
void BasebandProcessor::feed_channel_spectrum(
const buffer_c16_t channel,
const uint32_t filter_pass_frequency,
const uint32_t filter_stop_frequency
) {
channel_filter_pass_frequency = filter_pass_frequency;
channel_filter_stop_frequency = filter_stop_frequency;
channel_spectrum_decimator.feed(
channel,
[this](const buffer_c16_t data) {
this->post_channel_spectrum_message(data);
}
);
}
void BasebandProcessor::fill_audio_buffer(const buffer_s16_t audio) {
auto audio_buffer = audio::dma::tx_empty_buffer();;
for(size_t i=0; i<audio_buffer.count; i++) {
audio_buffer.p[i].left = audio_buffer.p[i].right = audio.p[i];
}
i2s::i2s0::tx_unmute();
feed_audio_stats(audio);
}
void BasebandProcessor::post_channel_stats_message(const ChannelStatistics statistics) {
channel_stats_message.statistics = statistics;
shared_memory.application_queue.push(channel_stats_message);
}
void BasebandProcessor::post_channel_spectrum_message(const buffer_c16_t data) {
if( !channel_spectrum_request_update ) {
fft_swap(data, channel_spectrum);
channel_spectrum_sampling_rate = data.sampling_rate;
channel_spectrum_request_update = true;
events_flag(EVT_MASK_SPECTRUM);
}
}
void BasebandProcessor::feed_audio_stats(const buffer_s16_t audio) {
audio_stats.feed(
audio,
[this](const AudioStatistics statistics) {
this->post_audio_stats_message(statistics);
}
);
}
void BasebandProcessor::post_audio_stats_message(const AudioStatistics statistics) {
audio_stats_message.statistics = statistics;
shared_memory.application_queue.push(audio_stats_message);
}

View File

@ -0,0 +1,76 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __BASEBAND_PROCESSOR_H__
#define __BASEBAND_PROCESSOR_H__
#include "dsp_types.hpp"
#include "complex.hpp"
#include "block_decimator.hpp"
#include "channel_stats_collector.hpp"
#include "audio_stats_collector.hpp"
#include <array>
#include <cstdint>
#include <complex>
class BasebandProcessor {
public:
virtual ~BasebandProcessor() = default;
virtual void execute(buffer_c8_t buffer) = 0;
void update_spectrum();
protected:
void feed_channel_stats(const buffer_c16_t channel);
void feed_channel_spectrum(
const buffer_c16_t channel,
const uint32_t filter_pass_frequency,
const uint32_t filter_stop_frequency
);
void fill_audio_buffer(const buffer_s16_t audio);
volatile bool channel_spectrum_request_update { false };
std::array<std::complex<float>, 256> channel_spectrum;
uint32_t channel_spectrum_sampling_rate { 0 };
uint32_t channel_filter_pass_frequency { 0 };
uint32_t channel_filter_stop_frequency { 0 };
private:
BlockDecimator<256> channel_spectrum_decimator { 4 };
ChannelStatsCollector channel_stats;
ChannelStatisticsMessage channel_stats_message;
AudioStatsCollector audio_stats;
AudioStatisticsMessage audio_stats_message;
void post_channel_stats_message(const ChannelStatistics statistics);
void post_channel_spectrum_message(const buffer_c16_t data);
void feed_audio_stats(const buffer_s16_t audio);
void post_audio_stats_message(const AudioStatistics statistics);
};
#endif/*__BASEBAND_PROCESSOR_H__*/

View File

@ -26,13 +26,25 @@
#include "dsp_types.hpp"
#include "message.hpp"
#include "utility.hpp"
#include "utility_m4.hpp"
#include <cstdint>
#include <cstddef>
class BasebandStatsCollector {
public:
BasebandStatsCollector(
const Thread* const thread_idle,
const Thread* const thread_main,
const Thread* const thread_rssi,
const Thread* const thread_baseband
) : thread_idle { thread_idle },
thread_main { thread_main },
thread_rssi { thread_rssi },
thread_baseband { thread_baseband }
{
}
template<typename Callback>
void process(buffer_c8_t buffer, Callback callback) {
samples += buffer.count;
@ -40,11 +52,21 @@ public:
const size_t report_samples = buffer.sampling_rate * report_interval;
const auto report_delta = samples - samples_last_report;
if( report_delta >= report_samples ) {
const auto idle_ticks = chSysGetIdleThread()->total_ticks;
BasebandStatistics statistics;
const auto idle_ticks = thread_idle->total_ticks;
statistics.idle_ticks = (idle_ticks - last_idle_ticks);
last_idle_ticks = idle_ticks;
const auto baseband_ticks = chThdSelf()->total_ticks;
const auto main_ticks = thread_main->total_ticks;
statistics.main_ticks = (main_ticks - last_main_ticks);
last_main_ticks = main_ticks;
const auto rssi_ticks = thread_rssi->total_ticks;
statistics.rssi_ticks = (rssi_ticks - last_rssi_ticks);
last_rssi_ticks = rssi_ticks;
const auto baseband_ticks = thread_baseband->total_ticks;
statistics.baseband_ticks = (baseband_ticks - last_baseband_ticks);
last_baseband_ticks = baseband_ticks;
@ -59,10 +81,15 @@ public:
private:
static constexpr float report_interval { 1.0f };
BasebandStatistics statistics;
size_t samples { 0 };
size_t samples_last_report { 0 };
const Thread* const thread_idle;
uint32_t last_idle_ticks { 0 };
const Thread* const thread_main;
uint32_t last_main_ticks { 0 };
const Thread* const thread_rssi;
uint32_t last_rssi_ticks { 0 };
const Thread* const thread_baseband;
uint32_t last_baseband_ticks { 0 };
};

View File

@ -24,7 +24,9 @@
#include <cstdint>
#include <cstddef>
#include <array>
#include "dsp_types.hpp"
#include "complex.hpp"
template<size_t N>

View File

@ -0,0 +1,84 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "channel_decimator.hpp"
buffer_c16_t ChannelDecimator::execute_decimation(buffer_c8_t buffer) {
const buffer_c16_t work_baseband_buffer {
work_baseband.data(),
work_baseband.size()
};
const buffer_s16_t work_audio_buffer {
(int16_t*)work_baseband.data(),
sizeof(work_baseband) / sizeof(int16_t)
};
/* 3.072MHz complex<int8_t>[2048], [-128, 127]
* -> Shift by -fs/4
* -> 3rd order CIC: -0.1dB @ 0.028fs, -1dB @ 0.088fs, -60dB @ 0.468fs
* -0.1dB @ 86kHz, -1dB @ 270kHz, -60dB @ 1.44MHz
* -> gain of 256
* -> decimation by 2
* -> 1.544MHz complex<int16_t>[1024], [-32768, 32512] */
const auto stage_0_out = translate.execute(buffer, work_baseband_buffer);
//if( fs_over_4_downconvert ) {
// // TODO:
//} else {
// Won't work until cic_0 will accept input type of buffer_c8_t.
// stage_0_out = cic_0.execute(buffer, work_baseband_buffer);
//}
/* 1.536MHz complex<int16_t>[1024], [-32768, 32512]
* -> 3rd order CIC: -0.1dB @ 0.028fs, -1dB @ 0.088fs, -60dB @ 0.468fs
* -0.1dB @ 43kHz, -1dB @ 136kHz, -60dB @ 723kHz
* -> gain of 8
* -> decimation by 2
* -> 768kHz complex<int16_t>[512], [-8192, 8128] */
auto cic_1_out = cic_1.execute(stage_0_out, work_baseband_buffer);
if( decimation_factor == DecimationFactor::By4 ) {
return cic_1_out;
}
/* 768kHz complex<int16_t>[512], [-32768, 32512]
* -> 3rd order CIC decimation by 2, gain of 1
* -> 384kHz complex<int16_t>[256], [-32768, 32512] */
auto cic_2_out = cic_2.execute(cic_1_out, work_baseband_buffer);
if( decimation_factor == DecimationFactor::By8 ) {
return cic_2_out;
}
/* 384kHz complex<int16_t>[256], [-32768, 32512]
* -> 3rd order CIC decimation by 2, gain of 1
* -> 192kHz complex<int16_t>[128], [-32768, 32512] */
auto cic_3_out = cic_3.execute(cic_2_out, work_baseband_buffer);
if( decimation_factor == DecimationFactor::By16 ) {
return cic_3_out;
}
/* 192kHz complex<int16_t>[128], [-32768, 32512]
* -> 3rd order CIC decimation by 2, gain of 1
* -> 96kHz complex<int16_t>[64], [-32768, 32512] */
auto cic_4_out = cic_4.execute(cic_3_out, work_baseband_buffer);
return cic_4_out;
}

View File

@ -0,0 +1,79 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __CHANNEL_DECIMATOR_H__
#define __CHANNEL_DECIMATOR_H__
#include "buffer.hpp"
#include "complex.hpp"
#include "dsp_decimate.hpp"
#include <array>
class ChannelDecimator {
public:
enum class DecimationFactor {
By4,
By8,
By16,
By32,
};
constexpr ChannelDecimator(
) : decimation_factor { DecimationFactor::By32 }
{
}
constexpr ChannelDecimator(
const DecimationFactor decimation_factor
) : decimation_factor { decimation_factor }
{
}
void set_decimation_factor(const DecimationFactor f) {
decimation_factor = f;
}
buffer_c16_t execute(buffer_c8_t buffer) {
auto decimated = execute_decimation(buffer);
return decimated;
}
private:
std::array<complex16_t, 1024> work_baseband;
//const bool fs_over_4_downconvert = true;
dsp::decimate::TranslateByFSOver4AndDecimateBy2CIC3 translate;
//dsp::decimate::DecimateBy2CIC3 cic_0;
dsp::decimate::DecimateBy2CIC3 cic_1;
dsp::decimate::DecimateBy2CIC3 cic_2;
dsp::decimate::DecimateBy2CIC3 cic_3;
dsp::decimate::DecimateBy2CIC3 cic_4;
DecimationFactor decimation_factor;
buffer_c16_t execute_decimation(buffer_c8_t buffer);
};
#endif/*__CHANNEL_DECIMATOR_H__*/

View File

@ -29,6 +29,8 @@
#include <cstdint>
#include <cstddef>
#include <hal.h>
class ChannelStatsCollector {
public:
template<typename Callback>
@ -47,13 +49,8 @@ public:
if( count >= samples_per_update ) {
const float max_squared_f = max_squared;
const float max_db_f = complex16_mag_squared_to_dbv_norm(max_squared_f);
const int32_t max_db = max_db_f;
const ChannelStatistics statistics {
.max_db = max_db,
.count = count,
};
callback(statistics);
const int32_t max_db = complex16_mag_squared_to_dbv_norm(max_squared_f);
callback({ max_db, count });
max_squared = 0;
count = 0;

View File

@ -20,12 +20,3 @@
*/
#include "clock_recovery.hpp"
void ClockRecovery::configure(
const uint32_t symbol_rate,
const uint32_t sampling_rate
) {
phase_increment = phase_increment_u32(
fractional_symbol_rate(symbol_rate, sampling_rate)
);
}

View File

@ -22,65 +22,157 @@
#ifndef __CLOCK_RECOVERY_H__
#define __CLOCK_RECOVERY_H__
#include <cstdint>
#include <cstddef>
#include <array>
#include <functional>
class ClockRecovery {
#include "linear_resampler.hpp"
namespace clock_recovery {
class GardnerTimingErrorDetector {
public:
void configure(
const uint32_t symbol_rate,
const uint32_t sampling_rate
);
static constexpr size_t samples_per_symbol { 2 };
/*
Expects retimed samples at a rate of twice the expected symbol rate.
Calculates timing error, sends symbol and error to handler.
*/
template<typename SymbolHandler>
void execute(
void operator()(
const float in,
SymbolHandler symbol_handler
) {
const bool phase_0 = (phase_last >> 31) & (!(phase >> 31));
const bool phase_180 = (!(phase_last >> 31)) & (phase >> 31);
phase_last = phase;
phase += phase_increment + phase_adjustment;
/* NOTE: Algorithm is sensitive to input magnitude. Timing error value
* will scale proportionally. Best practice is to use error sign only.
*/
t[2] = t[1];
t[1] = t[0];
t[0] = in;
if( phase_0 || phase_180 ) {
t2 = t1;
t1 = t0;
t0 = in;
if( symbol_phase == 0 ) {
const auto symbol = t[0];
const float lateness = (t[0] - t[2]) * t[1];
symbol_handler(symbol, lateness);
}
if( phase_0 ) {
symbol_handler(t0);
const float error = (t0 - t2) * t1;
// + error == late == decrease/slow phase
// - error == early == increase/fast phase
error_filtered = 0.75f * error_filtered + 0.25f * error;
// Correct phase (don't change frequency!)
phase_adjustment = -phase_increment * error_filtered / 200.0f;
}
symbol_phase = (symbol_phase + 1) % samples_per_symbol;
}
private:
uint32_t phase { 0 };
uint32_t phase_last { 0 };
uint32_t phase_adjustment { 0 };
uint32_t phase_increment { 0 };
float t0 { 0 };
float t1 { 0 };
float t2 { 0 };
float error_filtered { 0 };
std::array<float, 3> t { { 0.0f, 0.0f, 0.0f } };
size_t symbol_phase { 0 };
};
static constexpr float fractional_symbol_rate(
const uint32_t symbol_rate,
const uint32_t sampling_rate
) {
return float(symbol_rate) / float(sampling_rate);
class LinearErrorFilter {
public:
LinearErrorFilter(
const float filter_alpha = 0.95f,
const float error_weight = -1.0f
) : filter_alpha { filter_alpha },
error_weight { error_weight }
{
}
static constexpr uint32_t phase_increment_u32(const float fractional_symbol_rate) {
return 4294967296.0f * fractional_symbol_rate;
float operator()(
const float error
) {
error_filtered = filter_alpha * error_filtered + (1.0f - filter_alpha) * error;
return error_filtered * error_weight;
}
private:
const float filter_alpha;
const float error_weight;
float error_filtered { 0.0f };
};
class FixedErrorFilter {
public:
FixedErrorFilter(
) {
}
FixedErrorFilter(
const float weight
) : weight_ { weight }
{
}
float operator()(
const float lateness
) const {
return (lateness < 0.0f) ? weight() : -weight();
}
float weight() const {
return weight_;
}
private:
float weight_ { 1.0f / 16.0f };
};
template<typename ErrorFilter>
class ClockRecovery {
public:
ClockRecovery(
const float sampling_rate,
const float symbol_rate,
ErrorFilter error_filter,
std::function<void(const float)> symbol_handler
) : symbol_handler { symbol_handler }
{
configure(sampling_rate, symbol_rate, error_filter);
}
ClockRecovery(
std::function<void(const float)> symbol_handler
) : symbol_handler { symbol_handler }
{
}
void configure(
const float sampling_rate,
const float symbol_rate,
ErrorFilter error_filter
) {
resampler.configure(sampling_rate, symbol_rate * timing_error_detector.samples_per_symbol);
error_filter = error_filter;
}
void operator()(
const float baseband_sample
) {
resampler(baseband_sample,
[this](const float interpolated_sample) {
this->resampler_callback(interpolated_sample);
}
);
}
private:
dsp::interpolation::LinearResampler resampler;
GardnerTimingErrorDetector timing_error_detector;
ErrorFilter error_filter;
std::function<void(const float)> symbol_handler;
void resampler_callback(const float interpolated_sample) {
timing_error_detector(interpolated_sample,
[this](const float symbol, const float lateness) {
this->symbol_callback(symbol, lateness);
}
);
}
void symbol_callback(const float symbol, const float lateness) {
symbol_handler(symbol);
const float adjustment = error_filter(lateness);
resampler.advance(adjustment);
}
};
} /* namespace clock_recovery */
#endif/*__CLOCK_RECOVERY_H__*/

View File

@ -196,120 +196,38 @@ buffer_s16_t FIR64AndDecimateBy2Real::execute(
return { dst.p, src.count / 2, src.sampling_rate / 2 };
}
#if 0
size_t fir_and_decimate_by_2_complex(
const complex16_t* const src_start,
const size_t src_count,
complex16_t* const dst_start,
complex16_t* const z,
const complex16_t* const taps,
const size_t taps_count
buffer_c16_t FIRAndDecimateComplex::execute(
buffer_c16_t src,
buffer_c16_t dst
) {
/* int16_t input (sample count "n" must be multiple of 4)
* -> int16_t output, decimated by 2.
/* int16_t input (sample count "n" must be multiple of decimation_factor)
* -> int16_t output, decimated by decimation_factor.
* taps are normalized to 1 << 16 == 1.0.
*/
auto src_p = src_start;
const auto src_end = &src_start[src_count];
auto dst_p = dst_start;
const auto output_sampling_rate = src.sampling_rate / decimation_factor_;
const size_t output_samples = src.count / decimation_factor_;
sample_t* dst_p = dst.p;
const buffer_c16_t result { dst.p, output_samples, output_sampling_rate };
auto z_p = &z[0];
const sample_t* src_p = src.p;
size_t outer_count = output_samples;
while(outer_count > 0) {
/* Put new samples into delay buffer */
auto z_new_p = &samples_[taps_count_ - decimation_factor_];
for(size_t i=0; i<decimation_factor_; i++) {
*__SIMD32(z_new_p)++ = *__SIMD32(src_p)++;
}
while(src_p < src_end) {
/* Put two new samples into delay buffer */
*__SIMD32(z_p)++ = *__SIMD32(src_p)++;
*__SIMD32(z_p)++ = *__SIMD32(src_p)++;
size_t loop_count = taps_count_ / 8;
auto t_p = &taps_reversed_[0];
auto z_p = &samples_[0];
int64_t t_real = 0;
int64_t t_imag = 0;
auto t_p = &taps[0];
const auto z_end = &z[taps_count];
while(z_p < z_end) {
const auto tap0 = *__SIMD32(t_p)++;
const auto sample0 = *__SIMD32(z_p)++;
t_real = __SMLSLD(sample0, tap0, t_real);
t_imag = __SMLALDX(sample0, tap0, t_imag);
const auto tap1 = *__SIMD32(t_p)++;
const auto sample1 = *__SIMD32(z_p)++;
t_real = __SMLSLD(sample1, tap1, t_real);
t_imag = __SMLALDX(sample1, tap1, t_imag);
}
z_p = &z[0];
const auto t_end = &taps[taps_count];
while(t_p < t_end) {
const auto tap0 = *__SIMD32(t_p)++;
const auto sample0 = *__SIMD32(z_p)++;
t_real = __SMLSLD(sample0, tap0, t_real);
t_imag = __SMLALDX(sample0, tap0, t_imag);
const auto tap1 = *__SIMD32(t_p)++;
const auto sample1 = *__SIMD32(z_p)++;
t_real = __SMLSLD(sample1, tap1, t_real);
t_imag = __SMLALDX(sample1, tap1, t_imag);
}
if( z_p == z_end ) {
z_p = &z[0];
}
/* TODO: No rounding taking place here, so might be adding a bit of
* noise. Enough to be significant?
*/
*__SIMD32(dst_p)++ = __PKHBT(
t_real / 131072,
t_imag / 131072,
16
);
/*
*__SIMD32(dst_p)++ = __PKHBT(
__SSAT((t_real / 131072), 16),
__SSAT((t_imag / 131072), 16),
16
);
*/
}
return src_count / 2;
}
#endif
size_t fir_and_decimate_by_2_complex_fast(
const complex16_t* const src_start,
const size_t src_count,
complex16_t* const dst_start,
complex16_t* const z,
const complex16_t* const taps,
const size_t taps_count
) {
/* int16_t input (sample count "n" must be multiple of 4)
* -> int16_t output, decimated by 2.
* taps are normalized to 1 << 16 == 1.0.
*/
auto src_p = src_start;
auto dst_p = dst_start;
auto z_new_p = &z[0];
auto t_p = &taps[taps_count * 2];
while(src_p < &src_start[src_count]) {
/* Put two new samples into delay buffer */
*__SIMD32(z_new_p)++ = *__SIMD32(src_p)++;
*__SIMD32(z_new_p)++ = *__SIMD32(src_p)++;
t_p -= (taps_count + 2);
if( z_new_p == &z[taps_count] ) {
z_new_p = &z[0];
t_p = &taps[taps_count];
}
int64_t t_real = 0;
int64_t t_imag = 0;
auto z_p = &z[0];
while(z_p < &z[taps_count]) {
while(loop_count > 0) {
const auto tap0 = *__SIMD32(t_p)++;
const auto sample0 = *__SIMD32(z_p)++;
const auto tap1 = *__SIMD32(t_p)++;
@ -345,6 +263,8 @@ size_t fir_and_decimate_by_2_complex_fast(
t_imag = __SMLALDX(sample6, tap6, t_imag);
t_real = __SMLSLD(sample7, tap7, t_real);
t_imag = __SMLALDX(sample7, tap7, t_imag);
loop_count--;
}
/* TODO: Re-evaluate whether saturation is performed, normalization,
@ -359,9 +279,32 @@ size_t fir_and_decimate_by_2_complex_fast(
i_sat,
16
);
/* Shift sample buffer left/down by decimation factor. */
const size_t unroll_factor = 4;
size_t shift_count = (taps_count_ - decimation_factor_) / unroll_factor;
sample_t* t = &samples_[0];
const sample_t* s = &samples_[decimation_factor_];
while(shift_count > 0) {
*__SIMD32(t)++ = *__SIMD32(s)++;
*__SIMD32(t)++ = *__SIMD32(s)++;
*__SIMD32(t)++ = *__SIMD32(s)++;
*__SIMD32(t)++ = *__SIMD32(s)++;
shift_count--;
}
shift_count = (taps_count_ - decimation_factor_) % unroll_factor;
while(shift_count > 0) {
*(t++) = *(s++);
shift_count--;
}
outer_count--;
}
return src_count / 2;
return result;
}
buffer_s16_t DecimateBy2CIC4Real::execute(

View File

@ -24,6 +24,10 @@
#include <cstdint>
#include <array>
#include <memory>
#include <algorithm>
#include "utility.hpp"
#include "dsp_types.hpp"
@ -74,50 +78,46 @@ private:
const std::array<int16_t, taps_count>& taps;
};
size_t fir_and_decimate_by_2_complex(
const complex16_t* const src_start,
const size_t src_count,
complex16_t* const dst_start,
complex16_t* const z,
const complex16_t* const taps,
const size_t taps_count
);
size_t fir_and_decimate_by_2_complex_fast(
const complex16_t* const src_start,
const size_t src_count,
complex16_t* const dst_start,
complex16_t* const z,
const complex16_t* const taps,
const size_t taps_count
);
template<size_t taps_count>
class FIRAndDecimateBy2Complex {
class FIRAndDecimateComplex {
public:
using sample_t = complex16_t;
using tap_t = complex16_t;
using taps_t = tap_t[];
/* NOTE! Current code makes an assumption that block of samples to be
* processed will be a multiple of the taps_count.
*/
FIRAndDecimateBy2Complex(
const std::array<int16_t, taps_count>& real_taps
FIRAndDecimateComplex(
) : taps_count_ { 0 },
decimation_factor_ { 1 }
{
}
template<typename T>
void configure(
const T& taps,
const size_t decimation_factor
) {
for(size_t i=0; i<taps_count; i++) {
taps[ i] = real_taps[i];
taps[taps_count + i] = real_taps[i];
}
samples_ = std::make_unique<samples_t>(taps.size());
taps_reversed_ = std::make_unique<taps_t>(taps.size());
taps_count_ = taps.size();
decimation_factor_ = decimation_factor;
std::reverse_copy(taps.cbegin(), taps.cend(), &taps_reversed_[0]);
}
buffer_c16_t execute(
buffer_c16_t src,
buffer_c16_t dst
) {
const auto dst_count = fir_and_decimate_by_2_complex_fast(src.p, src.count, dst.p, z.data(), taps.data(), taps_count);
return { dst.p, dst_count, src.sampling_rate / 2 };
}
);
private:
std::array<complex16_t, taps_count * 2> taps;
std::array<complex16_t, taps_count> z;
using samples_t = sample_t[];
std::unique_ptr<samples_t> samples_;
std::unique_ptr<taps_t> taps_reversed_;
size_t taps_count_;
size_t decimation_factor_;
};
class DecimateBy2CIC4Real {

View File

@ -23,6 +23,7 @@
#include "complex.hpp"
#include "fxpt_atan2.hpp"
#include "utility_m4.hpp"
#include <hal.h>

View File

@ -55,9 +55,13 @@ public:
buffer_s16_t dst
);
void configure(const float sampling_rate, const float deviation_hz) {
k = static_cast<float>(32767.0f / (2.0 * pi * deviation_hz / sampling_rate));
}
private:
complex16_t::rep_type z_;
const float k;
float k;
};
} /* namespace demodulate */

View File

@ -0,0 +1,37 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __DSP_IIR_CONFIG_H__
#define __DSP_IIR_CONFIG_H__
#include "dsp_iir.hpp"
constexpr iir_biquad_config_t audio_hpf_config {
{ 0.93346032f, -1.86687724f, 0.93346032f },
{ 1.0f , -1.97730264f, 0.97773668f }
};
constexpr iir_biquad_config_t non_audio_hpf_config {
{ 0.51891061f, -0.95714180f, 0.51891061f },
{ 1.0f , -0.79878302f, 0.43960231f }
};
#endif/*__DSP_IIR_CONFIG_H__*/

View File

@ -0,0 +1,45 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "dsp_squelch.hpp"
#include <cstdint>
#include <array>
bool FMSquelch::execute(buffer_s16_t audio) {
// TODO: No hard-coded array size.
std::array<int16_t, N> squelch_energy_buffer;
const buffer_s16_t squelch_energy {
squelch_energy_buffer.data(),
squelch_energy_buffer.size()
};
non_audio_hpf.execute(audio, squelch_energy);
uint64_t max_squared = 0;
for(const auto sample : squelch_energy_buffer) {
const uint64_t sample_squared = sample * sample;
if( sample_squared > max_squared ) {
max_squared = sample_squared;
}
}
return (max_squared < (threshold * threshold));
}

View File

@ -0,0 +1,45 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __DSP_SQUELCH_H__
#define __DSP_SQUELCH_H__
#include "buffer.hpp"
#include "dsp_iir.hpp"
#include "dsp_iir_config.hpp"
#include <cstdint>
#include <cstddef>
class FMSquelch {
public:
bool execute(buffer_s16_t audio);
private:
static constexpr size_t N = 32;
static constexpr int16_t threshold = 3072;
// nyquist = 48000 / 2.0
// scipy.signal.iirdesign(wp=8000 / nyquist, ws= 4000 / nyquist, gpass=1, gstop=18, ftype='ellip')
IIRBiquadFilter non_audio_hpf { non_audio_hpf_config };
};
#endif/*__DSP_SQUELCH_H__*/

View File

@ -0,0 +1,54 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "irq_ipc_m4.hpp"
#include "ch.h"
#include "hal.h"
#include "event_m4.hpp"
#include "lpc43xx_cpp.hpp"
using namespace lpc43xx;
void m0apptxevent_interrupt_enable() {
nvicEnableVector(M0CORE_IRQn, CORTEX_PRIORITY_MASK(LPC43XX_M0APPTXEVENT_IRQ_PRIORITY));
}
void m0apptxevent_interrupt_disable() {
nvicDisableVector(M0CORE_IRQn);
}
extern "C" {
CH_IRQ_HANDLER(MAPP_IRQHandler) {
CH_IRQ_PROLOGUE();
chSysLockFromIsr();
events_flag_isr(EVT_MASK_BASEBAND);
chSysUnlockFromIsr();
creg::m0apptxevent::clear();
CH_IRQ_EPILOGUE();
}
}

View File

@ -0,0 +1,28 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __IRQ_IPC_M4_H__
#define __IRQ_IPC_M4_H__
void m0apptxevent_interrupt_enable();
void m0apptxevent_interrupt_disable();
#endif/*__IRQ_IPC_M4_H__*/

View File

@ -0,0 +1,69 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __LINEAR_RESAMPLER_H__
#define __LINEAR_RESAMPLER_H__
namespace dsp {
namespace interpolation {
class LinearResampler {
public:
void configure(
const float input_rate,
const float output_rate
) {
phase_increment = calculate_increment(input_rate, output_rate);
}
template<typename InterpolatedSampleHandler>
void operator()(
const float sample,
InterpolatedSampleHandler interpolated_sample_handler
) {
const float sample_delta = sample - last_sample;
while( phase < 1.0f ) {
const float interpolated_value = last_sample + phase * sample_delta;
interpolated_sample_handler(interpolated_value);
phase += phase_increment;
}
last_sample = sample;
phase -= 1.0f;
}
void advance(const float fraction) {
phase += (fraction * phase_increment);
}
private:
float last_sample { 0.0f };
float phase { 0.0f };
float phase_increment { 0.0f };
static constexpr float calculate_increment(const float input_rate, const float output_rate) {
return input_rate / output_rate;
}
};
} /* namespace interpolation */
} /* namespace dsp */
#endif/*__LINEAR_RESAMPLER_H__*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,89 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "matched_filter.hpp"
namespace dsp {
namespace matched_filter {
bool MatchedFilter::execute_once(
const sample_t input
) {
samples_[taps_count_ - decimation_factor_ + decimation_phase] = input;
advance_decimation_phase();
if( is_new_decimation_cycle() ) {
float sr_tr = 0.0f;
float si_tr = 0.0f;
float si_ti = 0.0f;
float sr_ti = 0.0f;
for(size_t n=0; n<taps_count_; n++) {
const auto sample = samples_[n];
const auto tap = taps_reversed_[n];
sr_tr += sample.real() * tap.real();
si_ti += sample.imag() * tap.imag();
si_tr += sample.imag() * tap.real();
sr_ti += sample.real() * tap.imag();
}
// N: complex multiple of samples and taps (conjugate, tap.i negated).
// P: complex multiply of samples and taps.
const auto r_n = sr_tr + si_ti;
const auto r_p = sr_tr - si_ti;
const auto i_n = si_tr - sr_ti;
const auto i_p = si_tr + sr_ti;
const auto mag_n = std::sqrt(r_n * r_n + i_n * i_n);
const auto mag_p = std::sqrt(r_p * r_p + i_p * i_p);
const auto diff = mag_p - mag_n;
output = diff;
shift_by_decimation_factor();
return true;
} else {
return false;
}
}
void MatchedFilter::shift_by_decimation_factor() {
const sample_t* s = &samples_[decimation_factor_];
sample_t* t = &samples_[0];
const size_t unroll_factor = 4;
size_t shift_count = (taps_count_ - decimation_factor_) / unroll_factor;
while(shift_count > 0) {
*t++ = *s++;
*t++ = *s++;
*t++ = *s++;
*t++ = *s++;
shift_count--;
}
shift_count = (taps_count_ - decimation_factor_) % unroll_factor;
while(shift_count > 0) {
*t++ = *s++;
shift_count--;
}
}
} /* namespace matched_filter */
} /* namespace dsp */

View File

@ -0,0 +1,101 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __MATCHED_FILTER_H__
#define __MATCHED_FILTER_H__
#include "utility.hpp"
#include <cstddef>
#include <complex>
#include <array>
#include <memory>
#include <algorithm>
#include <numeric>
namespace dsp {
namespace matched_filter {
// This filter contains "magic" (optimizations) that expect the taps to
// combine a low-pass filter with a complex sinusoid that performs shifting of
// the input signal to 0Hz/DC. This also means that the taps length must be
// a multiple of the complex sinusoid period.
class MatchedFilter {
public:
using sample_t = std::complex<float>;
using tap_t = std::complex<float>;
using taps_t = tap_t[];
template<class T>
MatchedFilter(
const T& taps,
size_t decimation_factor = 1
) {
configure(taps, decimation_factor);
}
template<class T>
void configure(
const T& taps,
size_t decimation_factor
) {
samples_ = std::make_unique<samples_t>(taps.size());
taps_reversed_ = std::make_unique<taps_t>(taps.size());
taps_count_ = taps.size();
decimation_factor_ = decimation_factor;
std::reverse_copy(taps.cbegin(), taps.cend(), &taps_reversed_[0]);
}
bool execute_once(const sample_t input);
float get_output() const {
return output;
}
private:
using samples_t = sample_t[];
std::unique_ptr<samples_t> samples_;
std::unique_ptr<taps_t> taps_reversed_;
size_t taps_count_ { 0 };
size_t decimation_factor_ { 1 };
size_t decimation_phase { 0 };
float output;
void shift_by_decimation_factor();
void advance_decimation_phase() {
decimation_phase = (decimation_phase + 1) % decimation_factor_;
}
bool is_new_decimation_cycle() const {
return (decimation_phase == 0);
}
};
} /* namespace matched_filter */
} /* namespace dsp */
#endif/*__MATCHED_FILTER_H__*/

View File

@ -41,3 +41,7 @@
//#define LPC_ADC1_IRQ_PRIORITY 4
#define LPC43XX_M0APPTXEVENT_IRQ_PRIORITY 4
/* M4 is initialized by M0, which has already started PLL1 */
#define LPC43XX_M4_CLK 200000000
#define LPC43XX_M4_CLK_SRC 0x09

View File

@ -20,15 +20,3 @@
*/
#include "packet_builder.hpp"
void PacketBuilder::configure(size_t new_payload_length) {
if( new_payload_length <= payload.size() ) {
payload_length = new_payload_length;
reset_state();
}
}
void PacketBuilder::reset_state() {
bits_received = 0;
state = State::AccessCodeSearch;
}

View File

@ -25,30 +25,62 @@
#include <cstdint>
#include <cstddef>
#include <bitset>
#include <functional>
#include "bit_pattern.hpp"
template<typename PreambleMatcher, typename UnstuffMatcher, typename EndMatcher>
class PacketBuilder {
public:
void configure(size_t new_payload_length);
using PayloadType = std::bitset<1024>;
using PayloadHandlerFunc = std::function<void(const PayloadType& payload, const size_t bits_received)>;
template<typename PayloadHandler>
void execute(
const uint_fast8_t symbol,
const bool access_code_found,
PayloadHandler payload_handler
PacketBuilder(
const PreambleMatcher preamble_matcher,
const UnstuffMatcher unstuff_matcher,
const EndMatcher end_matcher,
const PayloadHandlerFunc payload_handler
) : payload_handler { payload_handler },
preamble(preamble_matcher),
unstuff(unstuff_matcher),
end(end_matcher)
{
}
void configure(
const PreambleMatcher preamble_matcher,
const UnstuffMatcher unstuff_matcher
) {
preamble = preamble_matcher;
unstuff = unstuff_matcher;
reset_state();
}
void execute(
const uint_fast8_t symbol
) {
bit_history.add(symbol);
switch(state) {
case State::AccessCodeSearch:
if( access_code_found ) {
case State::Preamble:
if( preamble(bit_history, bits_received) ) {
state = State::Payload;
}
break;
case State::Payload:
if( bits_received < payload_length ) {
if( !unstuff(bit_history, bits_received) ) {
payload[bits_received++] = symbol;
} else {
}
if( end(bit_history, bits_received) ) {
payload_handler(payload, bits_received);
reset_state();
} else {
if( packet_truncated() ) {
reset_state();
}
}
break;
@ -60,16 +92,29 @@ public:
private:
enum State {
AccessCodeSearch,
Preamble,
Payload,
};
size_t payload_length { 0 };
size_t bits_received { 0 };
State state { State::AccessCodeSearch };
std::bitset<256> payload;
bool packet_truncated() const {
return bits_received >= payload.size();
}
void reset_state();
const PayloadHandlerFunc payload_handler;
BitHistory bit_history;
PreambleMatcher preamble;
UnstuffMatcher unstuff;
EndMatcher end;
size_t bits_received { 0 };
State state { State::Preamble };
PayloadType payload;
void reset_state() {
bits_received = 0;
state = State::Preamble;
}
};
#endif/*__PACKET_BUILDER_H__*/

View File

@ -0,0 +1,75 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "proc_ais.hpp"
#include "portapack_shared_memory.hpp"
#include "i2s.hpp"
using namespace lpc43xx;
void AISProcessor::execute(buffer_c8_t buffer) {
/* 2.4576MHz, 2048 samples */
auto decimator_out = decimator.execute(buffer);
/* 76.8kHz, 64 samples */
feed_channel_stats(decimator_out);
/* No spectrum display while AIS decoding.
feed_channel_spectrum(
channel,
decimator_out.sampling_rate * channel_filter_taps.pass_frequency_normalized,
decimator_out.sampling_rate * channel_filter_taps.stop_frequency_normalized
);
*/
for(size_t i=0; i<decimator_out.count; i++) {
// TODO: No idea why implicit cast int16_t->float is not allowed.
const std::complex<float> sample {
static_cast<float>(decimator_out.p[i].real()),
static_cast<float>(decimator_out.p[i].imag())
};
if( mf.execute_once(sample) ) {
clock_recovery(mf.get_output());
}
}
i2s::i2s0::tx_mute();
}
void AISProcessor::consume_symbol(
const float raw_symbol
) {
const uint_fast8_t sliced_symbol = (raw_symbol >= 0.0f) ? 1 : 0;
const auto decoded_symbol = nrzi_decode(sliced_symbol);
packet_builder.execute(decoded_symbol);
}
void AISProcessor::payload_handler(
const std::bitset<1024>& payload,
const size_t bits_received
) {
AISPacketMessage message;
message.packet.payload = payload;
message.packet.bits_received = bits_received;
shared_memory.application_queue.push(message);
}

View File

@ -0,0 +1,70 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __PROC_AIS_H__
#define __PROC_AIS_H__
#include "baseband_processor.hpp"
#include "channel_decimator.hpp"
#include "matched_filter.hpp"
#include "clock_recovery.hpp"
#include "symbol_coding.hpp"
#include "packet_builder.hpp"
#include "message.hpp"
#include <cstdint>
#include <cstddef>
#include <bitset>
#include "ais_baseband.hpp"
class AISProcessor : public BasebandProcessor {
public:
using payload_t = std::bitset<1024>;
void execute(buffer_c8_t buffer) override;
private:
ChannelDecimator decimator { ChannelDecimator::DecimationFactor::By32 };
dsp::matched_filter::MatchedFilter mf { baseband::ais::rrc_taps_76k8_4t_p, 4 };
clock_recovery::ClockRecovery<clock_recovery::FixedErrorFilter> clock_recovery {
19200, 9600, { 0.0555f },
[this](const float symbol) { this->consume_symbol(symbol); }
};
symbol_coding::NRZIDecoder nrzi_decode;
PacketBuilder<BitPattern, BitPattern, BitPattern> packet_builder {
{ 0b0101010101111110, 16, 1 },
{ 0b111110, 6 },
{ 0b01111110, 8 },
[this](const payload_t& payload, const size_t bits_received) {
this->payload_handler(payload, bits_received);
}
};
void consume_symbol(const float symbol);
void payload_handler(const payload_t& payload, const size_t bits_received);
};
#endif/*__PROC_AIS_H__*/

View File

@ -0,0 +1,59 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "proc_am_audio.hpp"
#include <cstdint>
void NarrowbandAMAudio::execute(buffer_c8_t buffer) {
auto decimator_out = decimator.execute(buffer);
const buffer_c16_t work_baseband_buffer {
(complex16_t*)decimator_out.p,
sizeof(*decimator_out.p) * decimator_out.count
};
/* 96kHz complex<int16_t>[64]
* -> FIR filter, <?kHz (0.???fs) pass, gain 1.0
* -> 48kHz int16_t[32] */
auto channel = channel_filter.execute(decimator_out, work_baseband_buffer);
// TODO: Feed channel_stats post-decimation data?
feed_channel_stats(channel);
feed_channel_spectrum(
channel,
decimator_out.sampling_rate * channel_filter_taps.pass_frequency_normalized,
decimator_out.sampling_rate * channel_filter_taps.stop_frequency_normalized
);
const buffer_s16_t work_audio_buffer {
(int16_t*)decimator_out.p,
sizeof(*decimator_out.p) * decimator_out.count
};
/* 48kHz complex<int16_t>[32]
* -> AM demodulation
* -> 48kHz int16_t[32] */
auto audio = demod.execute(channel, work_audio_buffer);
audio_hpf.execute_in_place(audio);
fill_audio_buffer(audio);
}

View File

@ -0,0 +1,51 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __PROC_AM_AUDIO_H__
#define __PROC_AM_AUDIO_H__
#include "baseband_processor.hpp"
#include "channel_decimator.hpp"
#include "dsp_decimate.hpp"
#include "dsp_demodulate.hpp"
#include "dsp_fir_taps.hpp"
#include "dsp_iir.hpp"
#include "dsp_iir_config.hpp"
class NarrowbandAMAudio : public BasebandProcessor {
public:
NarrowbandAMAudio() {
decimator.set_decimation_factor(ChannelDecimator::DecimationFactor::By32);
channel_filter.configure(channel_filter_taps.taps, 2);
}
void execute(buffer_c8_t buffer) override;
private:
ChannelDecimator decimator;
const fir_taps_real<64>& channel_filter_taps = taps_64_lp_031_070_tfilter;
dsp::decimate::FIRAndDecimateComplex channel_filter;
dsp::demodulate::AM demod;
IIRBiquadFilter audio_hpf { audio_hpf_config };
};
#endif/*__PROC_AM_AUDIO_H__*/

View File

@ -0,0 +1,74 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "proc_nfm_audio.hpp"
#include <cstdint>
#include <cstddef>
void NarrowbandFMAudio::execute(buffer_c8_t buffer) {
/* Called every 2048/3072000 second -- 1500Hz. */
auto decimator_out = decimator.execute(buffer);
const buffer_c16_t work_baseband_buffer {
(complex16_t*)decimator_out.p,
sizeof(*decimator_out.p) * decimator_out.count
};
/* 96kHz complex<int16_t>[64]
* -> FIR filter, <6kHz (0.063fs) pass, gain 1.0
* -> 48kHz int16_t[32] */
auto channel = channel_filter.execute(decimator_out, work_baseband_buffer);
// TODO: Feed channel_stats post-decimation data?
feed_channel_stats(channel);
feed_channel_spectrum(
channel,
decimator_out.sampling_rate * channel_filter_taps.pass_frequency_normalized,
decimator_out.sampling_rate * channel_filter_taps.stop_frequency_normalized
);
const buffer_s16_t work_audio_buffer {
(int16_t*)decimator_out.p,
sizeof(*decimator_out.p) * decimator_out.count
};
/* 48kHz complex<int16_t>[32]
* -> FM demodulation
* -> 48kHz int16_t[32] */
auto audio = demod.execute(channel, work_audio_buffer);
static uint64_t audio_present_history = 0;
const auto audio_present_now = squelch.execute(audio);
audio_present_history = (audio_present_history << 1) | (audio_present_now ? 1 : 0);
const bool audio_present = (audio_present_history != 0);
if( !audio_present ) {
// Zero audio buffer.
for(size_t i=0; i<audio.count; i++) {
audio.p[i] = 0;
}
}
audio_hpf.execute_in_place(audio);
fill_audio_buffer(audio);
}

View File

@ -0,0 +1,54 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __PROC_NFM_AUDIO_H__
#define __PROC_NFM_AUDIO_H__
#include "baseband_processor.hpp"
#include "channel_decimator.hpp"
#include "dsp_decimate.hpp"
#include "dsp_demodulate.hpp"
#include "dsp_fir_taps.hpp"
#include "dsp_iir.hpp"
#include "dsp_iir_config.hpp"
#include "dsp_squelch.hpp"
class NarrowbandFMAudio : public BasebandProcessor {
public:
NarrowbandFMAudio() {
decimator.set_decimation_factor(ChannelDecimator::DecimationFactor::By32);
channel_filter.configure(channel_filter_taps.taps, 2);
}
void execute(buffer_c8_t buffer) override;
private:
ChannelDecimator decimator;
const fir_taps_real<64>& channel_filter_taps = taps_64_lp_042_078_tfilter;
dsp::decimate::FIRAndDecimateComplex channel_filter;
dsp::demodulate::FM demod { 48000, 7500 };
IIRBiquadFilter audio_hpf { audio_hpf_config };
FMSquelch squelch;
};
#endif/*__PROC_NFM_AUDIO_H__*/

View File

@ -0,0 +1,73 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "proc_tpms.hpp"
#include "portapack_shared_memory.hpp"
#include "i2s.hpp"
using namespace lpc43xx;
void TPMSProcessor::execute(buffer_c8_t buffer) {
/* 2.4576MHz, 2048 samples */
auto decimator_out = decimator.execute(buffer);
/* 76.8kHz, 64 samples */
feed_channel_stats(decimator_out);
/* No spectrum display while FSK decoding.
feed_channel_spectrum(
channel,
decimator_out.sampling_rate * channel_filter_taps.pass_frequency_normalized,
decimator_out.sampling_rate * channel_filter_taps.stop_frequency_normalized
);
*/
for(size_t i=0; i<decimator_out.count; i++) {
// TODO: No idea why implicit cast int16_t->float is not allowed.
const std::complex<float> sample {
static_cast<float>(decimator_out.p[i].real()),
static_cast<float>(decimator_out.p[i].imag())
};
if( mf.execute_once(sample) ) {
clock_recovery(mf.get_output());
}
}
i2s::i2s0::tx_mute();
}
void TPMSProcessor::consume_symbol(
const float raw_symbol
) {
const uint_fast8_t sliced_symbol = (raw_symbol >= 0.0f) ? 1 : 0;
packet_builder.execute(sliced_symbol);
}
void TPMSProcessor::payload_handler(
const std::bitset<1024>& payload,
const size_t bits_received
) {
TPMSPacketMessage message;
message.packet.payload = payload;
message.packet.bits_received = bits_received;
shared_memory.application_queue.push(message);
}

View File

@ -0,0 +1,91 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __PROC_TPMS_H__
#define __PROC_TPMS_H__
#include "baseband_processor.hpp"
#include "channel_decimator.hpp"
#include "matched_filter.hpp"
#include "clock_recovery.hpp"
#include "symbol_coding.hpp"
#include "packet_builder.hpp"
#include "message.hpp"
#include <cstdint>
#include <cstddef>
#include <bitset>
struct NeverMatch {
bool operator()(const BitHistory&, const size_t) const {
return false;
}
};
struct FixedLength {
bool operator()(const BitHistory&, const size_t symbols_received) const {
return symbols_received >= length;
}
const size_t length;
};
// Translate+rectangular filter
// sample=153.6k, deviation=38400, symbol=19200
// Length: 8 taps, 1 symbols, 2 cycles of sinusoid
constexpr std::array<std::complex<float>, 8> rect_taps_153k6_1t_p { {
{ 1.2500000000e-01f, 0.0000000000e+00f }, { 7.6540424947e-18f, 1.2500000000e-01f },
{ -1.2500000000e-01f, 1.5308084989e-17f }, { -2.2962127484e-17f, -1.2500000000e-01f },
{ 1.2500000000e-01f, -3.0616169979e-17f }, { 3.8270212473e-17f, 1.2500000000e-01f },
{ -1.2500000000e-01f, 4.5924254968e-17f }, { -5.3578297463e-17f, -1.2500000000e-01f },
} };
class TPMSProcessor : public BasebandProcessor {
public:
using payload_t = std::bitset<1024>;
void execute(buffer_c8_t buffer) override;
private:
ChannelDecimator decimator { ChannelDecimator::DecimationFactor::By16 };
dsp::matched_filter::MatchedFilter mf { rect_taps_153k6_1t_p, 4 };
clock_recovery::ClockRecovery<clock_recovery::FixedErrorFilter> clock_recovery {
38400, 19200, { 0.0555f },
[this](const float symbol) { this->consume_symbol(symbol); }
};
PacketBuilder<BitPattern, NeverMatch, FixedLength> packet_builder {
{ 0b010101010101010101010101010110, 30, 1 },
{ },
{ 256 },
[this](const payload_t& payload, const size_t bits_received) {
this->payload_handler(payload, bits_received);
}
};
void consume_symbol(const float symbol);
void payload_handler(const payload_t& payload, const size_t bits_received);
};
#endif/*__PROC_TPMS_H__*/

View File

@ -0,0 +1,72 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "proc_wfm_audio.hpp"
#include <cstdint>
void WidebandFMAudio::execute(buffer_c8_t buffer) {
auto decimator_out = decimator.execute(buffer);
const buffer_s16_t work_audio_buffer {
(int16_t*)decimator_out.p,
sizeof(*decimator_out.p) * decimator_out.count
};
auto channel = decimator_out;
// TODO: Feed channel_stats post-decimation data?
feed_channel_stats(channel);
//feed_channel_spectrum(channel);
/* 768kHz complex<int16_t>[512]
* -> FM demodulation
* -> 768kHz int16_t[512] */
/* TODO: To improve adjacent channel rejection, implement complex channel filter:
* pass < +/- 100kHz, stop > +/- 200kHz
*/
auto audio_oversampled = demod.execute(decimator_out, work_audio_buffer);
/* 768kHz int16_t[512]
* -> 4th order CIC decimation by 2, gain of 1
* -> 384kHz int16_t[256] */
auto audio_8fs = audio_dec_1.execute(audio_oversampled, work_audio_buffer);
/* 384kHz int16_t[256]
* -> 4th order CIC decimation by 2, gain of 1
* -> 192kHz int16_t[128] */
auto audio_4fs = audio_dec_2.execute(audio_8fs, work_audio_buffer);
/* 192kHz int16_t[128]
* -> 4th order CIC decimation by 2, gain of 1
* -> 96kHz int16_t[64] */
auto audio_2fs = audio_dec_3.execute(audio_4fs, work_audio_buffer);
/* 96kHz int16_t[64]
* -> FIR filter, <15kHz (0.156fs) pass, >19kHz (0.198fs) stop, gain of 1
* -> 48kHz int16_t[32] */
auto audio = audio_filter.execute(audio_2fs, work_audio_buffer);
/* -> 48kHz int16_t[32] */
audio_hpf.execute_in_place(audio);
fill_audio_buffer(audio);
}

View File

@ -0,0 +1,55 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __PROC_WFM_AUDIO_H__
#define __PROC_WFM_AUDIO_H__
#include "baseband_processor.hpp"
#include "channel_decimator.hpp"
#include "dsp_decimate.hpp"
#include "dsp_demodulate.hpp"
#include "dsp_fir_taps.hpp"
#include "dsp_iir.hpp"
#include "dsp_iir_config.hpp"
class WidebandFMAudio : public BasebandProcessor {
public:
WidebandFMAudio() {
decimator.set_decimation_factor(ChannelDecimator::DecimationFactor::By4);
}
void execute(buffer_c8_t buffer) override;
private:
ChannelDecimator decimator;
dsp::demodulate::FM demod { 768000, 75000 };
dsp::decimate::DecimateBy2CIC4Real audio_dec_1;
dsp::decimate::DecimateBy2CIC4Real audio_dec_2;
dsp::decimate::DecimateBy2CIC4Real audio_dec_3;
const fir_taps_real<64>& audio_filter_taps = taps_64_lp_156_198;
dsp::decimate::FIR64AndDecimateBy2Real audio_filter { audio_filter_taps.taps };
IIRBiquadFilter audio_hpf { audio_hpf_config };
};
#endif/*__PROC_WFM_AUDIO_H__*/

View File

@ -0,0 +1,69 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "proc_wideband_spectrum.hpp"
#include "event_m4.hpp"
#include "i2s.hpp"
using namespace lpc43xx;
#include "dsp_fft.hpp"
#include <cstdint>
#include <cstddef>
#include <array>
void WidebandSpectrum::execute(buffer_c8_t buffer) {
// 2048 complex8_t samples per buffer.
// 102.4us per buffer. 20480 instruction cycles per buffer.
static int phase = 0;
if( phase == 0 ) {
std::fill(spectrum.begin(), spectrum.end(), 0);
}
if( (phase & 7) == 0 ) {
// TODO: Removed window-presum windowing, due to lack of available code RAM.
// TODO: Apply window to improve spectrum bin sidelobes.
for(size_t i=0; i<channel_spectrum.size(); i++) {
spectrum[i] += std::complex<float> { buffer.p[i].real(), buffer.p[i].imag() };
}
}
if( phase == 23 ) {
if( channel_spectrum_request_update == false ) {
fft_swap(spectrum, channel_spectrum);
channel_spectrum_sampling_rate = buffer.sampling_rate;
channel_filter_pass_frequency = 0;
channel_filter_stop_frequency = 0;
channel_spectrum_request_update = true;
events_flag(EVT_MASK_SPECTRUM);
phase = 0;
}
} else {
phase++;
}
i2s::i2s0::tx_mute();
}

View File

@ -0,0 +1,41 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __PROC_WIDEBAND_SPECTRUM_H__
#define __PROC_WIDEBAND_SPECTRUM_H__
#include "baseband_processor.hpp"
#include <cstddef>
#include <array>
#include <complex>
class WidebandSpectrum : public BasebandProcessor {
public:
void execute(buffer_c8_t buffer) override;
private:
size_t sample_count = 0;
std::array<std::complex<float>, 256> spectrum;
};
#endif/*__PROC_WIDEBAND_SPECTRUM_H__*/

View File

@ -37,6 +37,12 @@ public:
return;
}
if( statistics.count == 0 ) {
const auto value_0 = *p;
statistics.min = value_0;
statistics.max = value_0;
}
const auto end = &p[buffer.count];
while(p < end) {
const uint32_t value = *(p++);
@ -58,9 +64,6 @@ public:
callback(statistics);
statistics.accumulator = 0;
statistics.count = 0;
const auto value_0 = *p;
statistics.min = value_0;
statistics.max = value_0;
}
}

View File

@ -0,0 +1,44 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __SYMBOL_CODING_H__
#define __SYMBOL_CODING_H__
#include <cstdint>
#include <cstddef>
namespace symbol_coding {
class NRZIDecoder {
public:
uint_fast8_t operator()(const uint_fast8_t symbol) {
const auto out = (~(symbol ^ last)) & 1;
last = symbol;
return out;
}
private:
uint_fast8_t last { 0 };
};
} /* namespace symbol_coding */
#endif/*__SYMBOL_CODING_H__*/

View File

@ -39,6 +39,7 @@ COPT=-std=gnu99 \
-Wall -Wextra -Wstrict-prototypes \
$(CPUFLAGS) \
-DLPC43XX -DLPC43XX_M4 \
-DGIT_REVISION=\"$(GIT_REVISION)\" \
-Os \
-ffunction-sections \
-fdata-sections \

View File

@ -89,6 +89,10 @@ void systick_adjust_period(const uint32_t counts_per_tick) {
ritimer_start();
}
void systick_stop() {
ritimer_stop();
}
/**
* @brief Low level HAL driver initialization.
*

View File

@ -145,6 +145,7 @@ typedef uint32_t halrtcnt_t;
extern "C" {
#endif
void hal_lld_init(void);
void systick_stop(void);
void systick_adjust_period(const uint32_t counts_per_tick);
halclock_t halLPCGetSystemClock(void);
void halLPCSetSystemClock(const halclock_t new_frequency);

View File

@ -41,7 +41,7 @@
/* TODO: Somehow share this value between the M4 and M0 cores. The M0 always
* runs at the same speed as the M4 core.
*/
static halclock_t hal_clock_f = LPC43XX_M4_CLK_IRC;
static halclock_t hal_clock_f = LPC43XX_M4_CLK;
/*===========================================================================*/
/* Driver local functions. */
@ -63,6 +63,10 @@ void halLPCSetSystemClock(const halclock_t new_frequency) {
hal_clock_f = new_frequency;
}
void systick_stop() {
SysTick->CTRL &= ~(SysTick_CTRL_ENABLE_Msk | SysTick_CTRL_TICKINT_Msk);
}
void systick_adjust_period(const uint32_t counts_per_tick) {
SysTick->LOAD = counts_per_tick;
}
@ -74,7 +78,7 @@ void systick_adjust_period(const uint32_t counts_per_tick) {
*/
void hal_lld_init(void) {
LPC_CGU->BASE_M4_CLK.AUTOBLOCK = 1;
LPC_CGU->BASE_M4_CLK.CLK_SEL = 1;
LPC_CGU->BASE_M4_CLK.CLK_SEL = LPC43XX_M4_CLK_SRC;
/* SysTick initialization using the system clock.*/
systick_adjust_period(halLPCGetSystemClock() / CH_FREQUENCY - 1);

View File

@ -164,6 +164,7 @@ typedef uint32_t halrtcnt_t;
extern "C" {
#endif
void hal_lld_init(void);
void systick_stop(void);
void systick_adjust_period(const uint32_t counts_per_tick);
halclock_t halLPCGetSystemClock(void);
void halLPCSetSystemClock(const halclock_t new_frequency);

View File

@ -25,7 +25,6 @@ MEMORY
{
flash : org = 0x00000000, len = 128k /* SPIFI flash @ 0x140????? */
ram : org = 0x20000000, len = 64k /* AHB SRAM @ 0x20000000 */
nvram : org = 0x10088000, len = 8k /* Local SRAM, VBAT domain */
}
__ram_start__ = ORIGIN(ram);

View File

@ -0,0 +1,376 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "ais_baseband.hpp"
#include <cstdint>
#include <cstddef>
#include <cstdlib>
#include <string>
#include "crc.hpp"
// TODO: Move string formatting elsewhere!!!
#include "ui_widget.hpp"
namespace baseband {
template<typename T, typename BitRemap>
class FieldReader {
public:
constexpr FieldReader(
const T& data
) : data { data }
{
}
uint32_t read(const size_t start_bit, const size_t length) const {
uint32_t value = 0;
for(size_t i=start_bit; i<(start_bit + length); i++) {
value = (value << 1) | data[bit_remap(i)];
}
return value;
}
private:
const T& data;
const BitRemap bit_remap { };
};
namespace ais {
struct BitRemap {
size_t operator()(const size_t bit_index) const {
return bit_index ^ 7;
}
};
struct CRCBitRemap {
size_t operator()(const size_t bit_index) const {
return bit_index;
}
};
using FieldReader = baseband::FieldReader<std::bitset<1024>, BitRemap>;
using CRCFieldReader = baseband::FieldReader<std::bitset<1024>, CRCBitRemap>;
struct PacketLengthRange {
constexpr PacketLengthRange(
) : min_bytes { 0 },
max_bytes { 0 }
{
}
constexpr PacketLengthRange(
const uint16_t min_bits,
const uint16_t max_bits
) : min_bytes { static_cast<uint8_t>(min_bits / 8U) },
max_bytes { static_cast<uint8_t>(max_bits / 8U) }
{
// static_assert((min_bits & 7) == 0, "minimum bits not a multiple of 8");
// static_assert((max_bits & 7) == 0, "minimum bits not a multiple of 8");
}
bool contains(const size_t bit_count) const {
return !is_above(bit_count) && !is_below(bit_count);
}
bool is_above(const size_t bit_count) const {
return (min() > bit_count);
}
bool is_below(const size_t bit_count) const {
return (max() < bit_count);
}
size_t min() const {
return min_bytes * 8;
}
size_t max() const {
return max_bytes * 8;
}
private:
const uint8_t min_bytes;
const uint8_t max_bytes;
};
static constexpr std::array<PacketLengthRange, 64> packet_length_range { {
{ 0, 0 }, // 0
{ 168, 168 }, // 1
{ 168, 168 }, // 2
{ 168, 168 }, // 3
{ 168, 168 }, // 4
{ 424, 424 }, // 5
{ 0, 0 }, // 6
{ 0, 0 }, // 7
{ 0, 1008 }, // 8
{ 0, 0 }, // 9
{ 0, 0 }, // 10
{ 0, 0 }, // 11
{ 0, 0 }, // 12
{ 0, 0 }, // 13
{ 0, 0 }, // 14
{ 0, 0 }, // 15
{ 0, 0 }, // 16
{ 0, 0 }, // 17
{ 168, 168 }, // 18
{ 0, 0 }, // 19
{ 72, 160 }, // 20
{ 272, 360 }, // 21
{ 168, 168 }, // 22
{ 160, 160 }, // 23
{ 160, 168 }, // 24
{ 0, 168 }, // 25
{ 0, 0 }, // 26
{ 0, 0 }, // 27
{ 0, 0 }, // 28
{ 0, 0 }, // 29
{ 0, 0 }, // 30
{ 0, 0 }, // 31
} };
struct PacketLengthValidator {
bool operator()(const uint_fast8_t message_id, const size_t length) {
return packet_length_range[message_id].contains(length);
}
};
struct PacketTooLong {
bool operator()(const uint_fast8_t message_id, const size_t length) {
return packet_length_range[message_id].is_below(length);
}
};
struct CRCCheck {
bool operator()(const std::bitset<1024>& payload, const size_t data_length) {
CRCFieldReader field_crc { payload };
CRC<uint16_t> ais_fcs { 0x1021 };
uint16_t crc_calculated = 0xffff;
for(size_t i=0; i<data_length + 16; i+=8) {
if( i == data_length ) {
crc_calculated ^= 0xffff;
}
const uint8_t byte = field_crc.read(i, 8);
crc_calculated = ais_fcs.calculate_byte(crc_calculated, byte);
}
return crc_calculated == 0x0000;
}
};
static int32_t ais_latitude_normalized(
const FieldReader& field,
const size_t start_bit
) {
// Shifting and dividing is to sign-extend the source field.
// TODO: There's probably a more elegant way to do it.
return static_cast<int32_t>(field.read(start_bit, 27) << 5) / 32;
}
static int32_t ais_longitude_normalized(
const FieldReader& field,
const size_t start_bit
) {
// Shifting and dividing is to sign-extend the source field.
// TODO: There's probably a more elegant way to do it.
return static_cast<int32_t>(field.read(start_bit, 28) << 4) / 16;
}
static std::string ais_format_latlon_normalized(const int32_t normalized) {
const int32_t t = (normalized * 5) / 3;
const int32_t degrees = t / (100 * 10000);
const int32_t fraction = std::abs(t) % (100 * 10000);
return ui::to_string_dec_int(degrees) + "." + ui::to_string_dec_int(fraction, 6, '0');
}
static std::string ais_format_latitude(
const FieldReader& field,
const size_t start_bit
) {
const auto value = static_cast<int32_t>(field.read(start_bit, 27) << 5) / 32;
return ais_format_latlon_normalized(value);
}
static std::string ais_format_longitude(
const FieldReader& field,
const size_t start_bit
) {
const auto value = static_cast<int32_t>(field.read(start_bit, 28) << 4) / 16;
return ais_format_latlon_normalized(value);
}
struct ais_datetime {
uint16_t year;
uint8_t month;
uint8_t day;
uint8_t hour;
uint8_t minute;
uint8_t second;
};
static ais_datetime ais_get_datetime(
const FieldReader& field,
const size_t start_bit
) {
return {
static_cast<uint16_t>(field.read(start_bit + 0, 14)),
static_cast<uint8_t >(field.read(start_bit + 14, 4)),
static_cast<uint8_t >(field.read(start_bit + 18, 5)),
static_cast<uint8_t >(field.read(start_bit + 23, 5)),
static_cast<uint8_t >(field.read(start_bit + 28, 6)),
static_cast<uint8_t >(field.read(start_bit + 34, 6)),
};
}
static std::string ais_format_datetime(
const FieldReader& field,
const size_t start_bit
) {
const auto datetime = ais_get_datetime(field, start_bit);
return ui::to_string_dec_uint(datetime.year, 4) + "/" +
ui::to_string_dec_uint(datetime.month, 2, '0') + "/" +
ui::to_string_dec_uint(datetime.day, 2, '0') + " " +
ui::to_string_dec_uint(datetime.hour, 2, '0') + ":" +
ui::to_string_dec_uint(datetime.minute, 2, '0') + ":" +
ui::to_string_dec_uint(datetime.second, 2, '0');
}
static char ais_char_to_ascii(const uint8_t c) {
return (c ^ 32) + 32;
}
static std::string ais_read_text(
const FieldReader& field,
const size_t start_bit,
const size_t character_count
) {
std::string result;
const size_t character_length = 6;
const size_t end_bit = start_bit + character_count * character_length;
for(size_t i=start_bit; i<end_bit; i+=character_length) {
result += ais_char_to_ascii(field.read(i, character_length));
}
return result;
}
static std::string ais_format_navigational_status(const unsigned int value) {
switch(value) {
case 0: return "under way w/engine";
case 1: return "at anchor";
case 2: return "not under command";
case 3: return "restricted maneuv";
case 4: return "constrained draught";
case 5: return "moored";
case 6: return "aground";
case 7: return "fishing";
case 8: return "sailing";
case 9: case 10: case 13: return "reserved";
case 11: return "towing astern";
case 12: return "towing ahead/along";
case 14: return "SART/MOB/EPIRB";
case 15: return "undefined";
default: return "unexpected";
}
}
decoded_packet packet_decode(const std::bitset<1024>& payload, const size_t payload_length) {
// TODO: Unstuff here, not in baseband!
// Subtract end flag (8 bits) - one unstuffing bit (occurs during end flag).
const size_t data_and_fcs_length = payload_length - 7;
if( data_and_fcs_length < 38 ) {
return { "short " + ui::to_string_dec_uint(data_and_fcs_length, 3), "" };
}
const size_t extra_bits = data_and_fcs_length & 7;
if( extra_bits != 0 ) {
return { "extra bits " + ui::to_string_dec_uint(data_and_fcs_length, 3), "" };
}
FieldReader field { payload };
const auto message_id = field.read(0, 6);
const size_t data_length = data_and_fcs_length - 16;
PacketLengthValidator packet_length_valid;
if( !packet_length_valid(message_id, data_length) ) {
return { "bad length " + ui::to_string_dec_uint(data_length, 3), "" };
}
CRCCheck crc_ok;
if( !crc_ok(payload, data_length) ) {
return { "crc", "" };
}
const auto source_id = field.read(8, 30);
std::string result { ui::to_string_dec_uint(message_id, 2) + " " + ui::to_string_dec_uint(source_id, 10) };
switch(message_id) {
case 1:
case 2:
case 3:
{
const auto navigational_status = field.read(38, 4);
result += " " + ais_format_navigational_status(navigational_status);
result += " " + ais_format_latlon_normalized(ais_latitude_normalized(field, 89));
result += " " + ais_format_latlon_normalized(ais_longitude_normalized(field, 61));
}
break;
case 4:
{
result += " " + ais_format_datetime(field, 38);
result += " " + ais_format_latlon_normalized(ais_latitude_normalized(field, 107));
result += " " + ais_format_latlon_normalized(ais_longitude_normalized(field, 79));
}
break;
case 5:
{
const auto call_sign = ais_read_text(field, 70, 7);
const auto name = ais_read_text(field, 112, 20);
const auto destination = ais_read_text(field, 302, 20);
result += " \"" + call_sign + "\" \"" + name + "\" \"" + destination + "\"";
}
break;
case 21:
{
const auto name = ais_read_text(field, 43, 20);
result += " \"" + name + "\" " + ais_format_latitude(field, 192) + " " + ais_format_longitude(field, 164);
}
break;
default:
break;
}
return { "OK", result };
}
} /* namespace ais */
} /* namespace baseband */

View File

@ -0,0 +1,67 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __AIS_BASEBAND_H__
#define __AIS_BASEBAND_H__
#include <cstdint>
#include <cstddef>
#include <complex>
#include <array>
#include <bitset>
#include <utility>
namespace baseband {
namespace ais {
// RRC length should be about 4 x the symbol length (4T) to do a good job of
// cleaning up ISI.
// Translate+RRC filter
// sample=76.8k, deviation=2400, b=0.5, symbol=9600
// Length: 32 taps, 4 symbols, 1 cycle of sinusoid
constexpr std::array<std::complex<float>, 32> rrc_taps_76k8_4t_p { {
{ 5.3368736990e-03f, 0.0000000000e+00f }, { 4.6850211151e-03f, 9.3190864122e-04f },
{ 1.7970187432e-03f, 7.4434953528e-04f }, { -2.5478608559e-03f, -1.7024261963e-03f },
{ -6.6710920858e-03f, -6.6710920858e-03f }, { -8.6960320791e-03f, -1.3014531722e-02f },
{ -7.5474785839e-03f, -1.8221225159e-02f }, { -3.8115552023e-03f, -1.9161981995e-02f },
{ -8.1697309033e-19f, -1.3342183083e-02f }, { 3.6940784220e-05f, -1.8571386338e-04f },
{ -7.5474785839e-03f, 1.8221225159e-02f }, { -2.4954265902e-02f, 3.7346698152e-02f },
{ -5.1450054092e-02f, 5.1450054092e-02f }, { -8.3018814119e-02f, 5.5471398140e-02f },
{ -1.1321218147e-01f, 4.6894020990e-02f }, { -1.3498960022e-01f, 2.6851100952e-02f },
{ -1.4292666316e-01f, 1.7503468055e-17f }, { -1.3498960022e-01f, -2.6851100952e-02f },
{ -1.1321218147e-01f, -4.6894020990e-02f }, { -8.3018814119e-02f, -5.5471398140e-02f },
{ -5.1450054092e-02f, -5.1450054092e-02f }, { -2.4954265902e-02f, -3.7346698152e-02f },
{ -7.5474785839e-03f, -1.8221225159e-02f }, { 3.6940784220e-05f, 1.8571386338e-04f },
{ 2.4509192710e-18f, 1.3342183083e-02f }, { -3.8115552023e-03f, 1.9161981995e-02f },
{ -7.5474785839e-03f, 1.8221225159e-02f }, { -8.6960320791e-03f, 1.3014531722e-02f },
{ -6.6710920858e-03f, 6.6710920858e-03f }, { -2.5478608559e-03f, 1.7024261963e-03f },
{ 1.7970187432e-03f, -7.4434953528e-04f }, { 4.6850211151e-03f, -9.3190864122e-04f },
} };
using decoded_packet = std::pair<std::string, std::string>;
decoded_packet packet_decode(const std::bitset<1024>& data, const size_t data_length);
} /* namespace ais */
} /* namespace baseband */
#endif/*__AIS_BASEBAND_H__*/

View File

@ -0,0 +1,73 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __BIT_PATTERN_H__
#define __BIT_PATTERN_H__
#include <cstdint>
#include <cstddef>
class BitHistory {
public:
void add(const uint_fast8_t bit) {
history = (history << 1) | (bit & 1);
}
uint32_t value() const {
return history;
}
private:
uint32_t history { 0 };
};
class BitPattern {
public:
constexpr BitPattern(
) : code_ { 0 },
mask_ { 0 },
maximum_hanning_distance_ { 0 }
{
}
constexpr BitPattern(
const uint32_t code,
const size_t code_length,
const size_t maximum_hanning_distance = 0
) : code_ { code },
mask_ { (1U << code_length) - 1U },
maximum_hanning_distance_ { maximum_hanning_distance }
{
}
bool operator()(const BitHistory& history, const size_t) const {
const auto delta_bits = (history.value() ^ code_) & mask_;
const size_t count = __builtin_popcountl(delta_bits);
return (count <= maximum_hanning_distance_);
}
private:
uint32_t code_;
uint32_t mask_;
size_t maximum_hanning_distance_;
};
#endif/*__BIT_PATTERN_H__*/

View File

@ -0,0 +1,40 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "chibios_cpp.hpp"
#include <ch.h>
void* operator new(size_t size) {
return chHeapAlloc(0x0, size);
}
void* operator new[](size_t size) {
return chHeapAlloc(0x0, size);
}
void operator delete(void* p) noexcept {
chHeapFree(p);
}
void operator delete[](void* p) noexcept {
chHeapFree(p);
}

View File

@ -19,31 +19,16 @@
* Boston, MA 02110-1301, USA.
*/
#ifndef __ACCESS_CODE_CORRELATOR_H__
#define __ACCESS_CODE_CORRELATOR_H__
#ifndef __CHIBIOS_CPP_H__
#define __CHIBIOS_CPP_H__
#include <cstdint>
#include <cstddef>
class AccessCodeCorrelator {
public:
void configure(
const uint32_t new_code,
const size_t new_code_length,
const size_t new_maximum_hamming_distance
);
/* Override new/delete to use Chibi/OS heap functions */
/* NOTE: Do not inline these, it doesn't work. ;-) */
void* operator new(size_t size);
void* operator new[](size_t size);
void operator delete(void* p);
void operator delete[](void* p);
bool execute(const uint_fast8_t in);
private:
uint32_t code { 0 };
uint32_t mask { 0 };
uint32_t history { 0 };
size_t maximum_hamming_distance { 0 };
static constexpr uint32_t mask_value(const size_t n) {
return static_cast<uint32_t>((1ULL << n) - 1ULL);
}
};
#endif/*__ACCESS_CODE_CORRELATOR_H__*/
#endif/*__CHIBIOS_CPP_H__*/

Some files were not shown because too many files have changed in this diff Show More