Merged remote-tracking branch 'upstream/master'

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

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

@@ -0,0 +1,50 @@
/*
* 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_rtc.hpp"
#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();
}
}

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,