mirror of
https://github.com/eried/portapack-mayhem.git
synced 2025-08-02 03:26:40 -04:00
Merge remote-tracking branch 'upstream/master'
This commit is contained in:
commit
c2a9ed7d9b
46 changed files with 13951 additions and 12343 deletions
|
@ -117,6 +117,7 @@ set(CPPSRC
|
|||
${COMMON}/message_queue.cpp
|
||||
${COMMON}/hackrf_hal.cpp
|
||||
portapack.cpp
|
||||
${COMMON}/backlight.cpp
|
||||
${COMMON}/portapack_shared_memory.cpp
|
||||
baseband_api.cpp
|
||||
${COMMON}/portapack_persistent_memory.cpp
|
||||
|
|
|
@ -125,11 +125,12 @@ void EventDispatcher::set_display_sleep(const bool sleep) {
|
|||
// TODO: Distribute display sleep message more broadly, shut down data generation
|
||||
// on baseband side, since all that data is being discarded during sleep.
|
||||
if( sleep ) {
|
||||
portapack::io.lcd_backlight(false);
|
||||
portapack::backlight()->off();
|
||||
portapack::display.sleep();
|
||||
} else {
|
||||
portapack::display.wake();
|
||||
portapack::io.lcd_backlight(true);
|
||||
// Don't turn on backlight here.
|
||||
// Let frame sync handler turn on backlight after repaint.
|
||||
}
|
||||
EventDispatcher::display_sleep = sleep;
|
||||
};
|
||||
|
@ -284,6 +285,8 @@ void EventDispatcher::handle_lcd_frame_sync() {
|
|||
DisplayFrameSyncMessage message;
|
||||
message_map.send(&message);
|
||||
painter.paint_widget_tree(top_widget);
|
||||
|
||||
portapack::backlight()->on();
|
||||
}
|
||||
|
||||
void EventDispatcher::handle_switches() {
|
||||
|
|
|
@ -38,9 +38,13 @@
|
|||
|
||||
#include <cstdint>
|
||||
|
||||
constexpr auto EVT_MASK_RTC_TICK = EVENT_MASK(0);
|
||||
constexpr auto EVT_MASK_LCD_FRAME_SYNC = EVENT_MASK(1);
|
||||
constexpr auto EVT_MASK_SWITCHES = EVENT_MASK(3);
|
||||
constexpr auto EVT_MASK_ENCODER = EVENT_MASK(4);
|
||||
constexpr auto EVT_MASK_TOUCH = EVENT_MASK(5);
|
||||
constexpr auto EVT_MASK_APPLICATION = EVENT_MASK(6);
|
||||
constexpr auto EVT_MASK_LOCAL = EVENT_MASK(7);
|
||||
|
||||
class EventDispatcher {
|
||||
public:
|
||||
|
@ -65,14 +69,6 @@ public:
|
|||
}
|
||||
}
|
||||
|
||||
static inline void event_isr_rtc_tick() {
|
||||
events_flag_isr(EVT_MASK_RTC_TICK);
|
||||
}
|
||||
|
||||
static inline void event_isr_lcd_frame_sync() {
|
||||
events_flag_isr(EVT_MASK_LCD_FRAME_SYNC);
|
||||
}
|
||||
|
||||
static inline void events_flag(const eventmask_t events) {
|
||||
if( thread_event_loop ) {
|
||||
chEvtSignal(thread_event_loop, events);
|
||||
|
@ -92,11 +88,6 @@ public:
|
|||
}
|
||||
|
||||
private:
|
||||
static constexpr auto EVT_MASK_RTC_TICK = EVENT_MASK(0);
|
||||
static constexpr auto EVT_MASK_LCD_FRAME_SYNC = EVENT_MASK(1);
|
||||
static constexpr auto EVT_MASK_APPLICATION = EVENT_MASK(6);
|
||||
static constexpr auto EVT_MASK_LOCAL = EVENT_MASK(7);
|
||||
|
||||
static Thread* thread_event_loop;
|
||||
|
||||
touch::Manager touch_manager { };
|
||||
|
|
|
@ -40,6 +40,8 @@
|
|||
#include "hackrf_hal.hpp"
|
||||
using namespace hackrf::one;
|
||||
|
||||
static Thread* thread_controls_event = NULL;
|
||||
|
||||
static std::array<Debounce, 7> switch_debounce;
|
||||
|
||||
static Encoder encoder;
|
||||
|
@ -156,7 +158,7 @@ void timer0_callback(GPTDriver* const) {
|
|||
/* Signal event loop */
|
||||
if( event_mask ) {
|
||||
chSysLockFromIsr();
|
||||
EventDispatcher::events_flag_isr(event_mask);
|
||||
chEvtSignalI(thread_controls_event, event_mask);
|
||||
chSysUnlockFromIsr();
|
||||
}
|
||||
}
|
||||
|
@ -176,6 +178,8 @@ static GPTConfig timer0_config {
|
|||
};
|
||||
|
||||
void controls_init() {
|
||||
thread_controls_event = chThdSelf();
|
||||
|
||||
touch::adc::start();
|
||||
|
||||
/* GPT timer 0 is used to scan user interface controls -- touch screen,
|
||||
|
|
|
@ -28,7 +28,10 @@
|
|||
|
||||
#include "portapack_hal.hpp"
|
||||
|
||||
static Thread* thread_lcd_frame_event = NULL;
|
||||
|
||||
static void pin_int4_interrupt_enable() {
|
||||
thread_lcd_frame_event = chThdSelf();
|
||||
nvicEnableVector(PIN_INT4_IRQn, CORTEX_PRIORITY_MASK(LPC43XX_PIN_INT4_IRQ_PRIORITY));
|
||||
}
|
||||
|
||||
|
@ -54,7 +57,7 @@ CH_IRQ_HANDLER(PIN_INT4_IRQHandler) {
|
|||
CH_IRQ_PROLOGUE();
|
||||
|
||||
chSysLockFromIsr();
|
||||
EventDispatcher::event_isr_lcd_frame_sync();
|
||||
chEvtSignalI(thread_lcd_frame_event, EVT_MASK_LCD_FRAME_SYNC);
|
||||
chSysUnlockFromIsr();
|
||||
|
||||
LPC_GPIO_INT->IST = (1U << 4);
|
||||
|
|
|
@ -27,8 +27,11 @@
|
|||
using namespace lpc43xx;
|
||||
|
||||
#include "event_m0.hpp"
|
||||
|
||||
|
||||
static Thread* thread_rtc_event = NULL;
|
||||
|
||||
void rtc_interrupt_enable() {
|
||||
thread_rtc_event = chThdSelf();
|
||||
rtc::interrupt::enable_second_inc();
|
||||
nvicEnableVector(RTC_IRQn, CORTEX_PRIORITY_MASK(LPC_RTC_IRQ_PRIORITY));
|
||||
}
|
||||
|
@ -39,7 +42,7 @@ CH_IRQ_HANDLER(RTC_IRQHandler) {
|
|||
CH_IRQ_PROLOGUE();
|
||||
|
||||
chSysLockFromIsr();
|
||||
EventDispatcher::event_isr_rtc_tick();
|
||||
chEvtSignalI(thread_rtc_event, EVT_MASK_RTC_TICK);
|
||||
chSysUnlockFromIsr();
|
||||
|
||||
rtc::interrupt::clear_all();
|
||||
|
|
|
@ -38,13 +38,11 @@
|
|||
|
||||
|
||||
#define LPC43XX_I2C_USE_I2C0 TRUE
|
||||
#define LPC43XX_I2C_USE_I2C1 TRUE
|
||||
|
||||
/*
|
||||
* SPI driver system settings.
|
||||
*/
|
||||
|
||||
#define LPC_SPI_USE_SSP0 TRUE
|
||||
#define LPC_SPI_USE_SSP1 TRUE
|
||||
|
||||
|
||||
|
|
|
@ -31,6 +31,7 @@ using namespace hackrf::one;
|
|||
|
||||
#include "clock_manager.hpp"
|
||||
|
||||
#include "backlight.hpp"
|
||||
#include "touch_adc.hpp"
|
||||
#include "audio.hpp"
|
||||
|
||||
|
@ -48,18 +49,20 @@ namespace portapack {
|
|||
|
||||
portapack::IO io {
|
||||
portapack::gpio_dir,
|
||||
portapack::gpio_lcd_rd,
|
||||
portapack::gpio_lcd_wr,
|
||||
portapack::gpio_lcd_rdx,
|
||||
portapack::gpio_lcd_wrx,
|
||||
portapack::gpio_io_stbx,
|
||||
portapack::gpio_addr,
|
||||
portapack::gpio_lcd_te,
|
||||
portapack::gpio_unused,
|
||||
};
|
||||
|
||||
portapack::BacklightCAT4004 backlight_cat4004;
|
||||
portapack::BacklightOnOff backlight_on_off;
|
||||
|
||||
lcd::ILI9341 display;
|
||||
|
||||
I2C i2c0(&I2CD0);
|
||||
SPI ssp0(&SPID1);
|
||||
SPI ssp1(&SPID2);
|
||||
|
||||
si5351::Si5351 clock_generator {
|
||||
|
@ -152,6 +155,65 @@ static const portapack::cpld::Config& portapack_cpld_config() {
|
|||
;
|
||||
}
|
||||
|
||||
Backlight* backlight() {
|
||||
return (portapack_model() == PortaPackModel::R2_20170522)
|
||||
? static_cast<portapack::Backlight*>(&backlight_cat4004)
|
||||
: static_cast<portapack::Backlight*>(&backlight_on_off);
|
||||
}
|
||||
|
||||
static void configure_unused_mcu_peripherals(const bool enabled) {
|
||||
/* Disabling these peripherals reduces "idle" (PortaPack at main
|
||||
* menu) current by 42mA.
|
||||
*/
|
||||
|
||||
/* Some surprising peripherals in use by PortaPack firmware:
|
||||
*
|
||||
* RITIMER: M0 SysTick substitute (because M0 has no SysTick)
|
||||
* TIMER3: M0 cycle/PCLK counter
|
||||
*/
|
||||
|
||||
const uint32_t clock_run_state = enabled ? 1 : 0;
|
||||
|
||||
LPC_CCU1->CLK_APB3_I2C1_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_APB3_DAC_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_APB3_CAN0_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_APB1_MOTOCON_PWM_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_APB1_CAN1_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_LCD_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_ETHERNET_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_USB0_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_EMC_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_SCT_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_USB1_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_EMCDIV_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_WWDT_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_USART0_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_UART1_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_SSP0_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_TIMER1_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_USART2_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_USART3_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_TIMER2_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_M4_QEI_CFG.RUN = clock_run_state;
|
||||
|
||||
LPC_CCU1->CLK_USB1_CFG.RUN = clock_run_state;
|
||||
LPC_CCU1->CLK_SPI_CFG.RUN = clock_run_state;
|
||||
|
||||
LPC_CCU2->CLK_APB2_USART3_CFG.RUN = clock_run_state;
|
||||
LPC_CCU2->CLK_APB2_USART2_CFG.RUN = clock_run_state;
|
||||
LPC_CCU2->CLK_APB0_UART1_CFG.RUN = clock_run_state;
|
||||
LPC_CCU2->CLK_APB0_USART0_CFG.RUN = clock_run_state;
|
||||
LPC_CCU2->CLK_APB0_SSP0_CFG.RUN = clock_run_state;
|
||||
}
|
||||
|
||||
static void disable_unused_mcu_peripheral_clocks() {
|
||||
configure_unused_mcu_peripherals(false);
|
||||
}
|
||||
|
||||
static void enable_unused_mcu_peripheral_clocks() {
|
||||
configure_unused_mcu_peripherals(true);
|
||||
}
|
||||
|
||||
static void shutdown_base() {
|
||||
clock_manager.shutdown();
|
||||
|
||||
|
@ -162,6 +224,8 @@ static void shutdown_base() {
|
|||
|
||||
systick_stop();
|
||||
|
||||
enable_unused_mcu_peripheral_clocks();
|
||||
|
||||
hackrf::one::reset();
|
||||
}
|
||||
|
||||
|
@ -190,6 +254,10 @@ bool init() {
|
|||
| (0U << 15) // SDA: Enable input glitch filter
|
||||
;
|
||||
|
||||
disable_unused_mcu_peripheral_clocks();
|
||||
|
||||
LPC_CREG->CREG0 |= (1 << 5); // Disable USB0 PHY
|
||||
|
||||
power.init();
|
||||
|
||||
gpio_max5864_select.set();
|
||||
|
@ -235,6 +303,7 @@ bool init() {
|
|||
void shutdown() {
|
||||
gpdma::controller.disable();
|
||||
|
||||
backlight()->off();
|
||||
display.shutdown();
|
||||
|
||||
radio::disable();
|
||||
|
|
|
@ -19,6 +19,8 @@
|
|||
* Boston, MA 02110-1301, USA.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "portapack_io.hpp"
|
||||
|
||||
#include "receiver_model.hpp"
|
||||
|
@ -28,6 +30,7 @@
|
|||
#include "spi_pp.hpp"
|
||||
#include "si5351.hpp"
|
||||
#include "lcd_ili9341.hpp"
|
||||
#include "backlight.hpp"
|
||||
|
||||
#include "radio.hpp"
|
||||
#include "clock_manager.hpp"
|
||||
|
@ -40,7 +43,6 @@ extern portapack::IO io;
|
|||
extern lcd::ILI9341 display;
|
||||
|
||||
extern I2C i2c0;
|
||||
extern SPI ssp0;
|
||||
extern SPI ssp1;
|
||||
|
||||
extern si5351::Si5351 clock_generator;
|
||||
|
@ -56,4 +58,6 @@ extern TemperatureLogger temperature_logger;
|
|||
bool init();
|
||||
void shutdown();
|
||||
|
||||
Backlight* backlight();
|
||||
|
||||
} /* namespace portapack */
|
||||
|
|
|
@ -586,10 +586,18 @@ void sdc_lld_start(SDCDriver *sdcp) {
|
|||
sdio_reset();
|
||||
sdio_reset_card();
|
||||
|
||||
// UM10503 recommendation
|
||||
// Test jig tests:
|
||||
// SAMPLE_DELAY Write Read SDC FAIL OK
|
||||
// 0 OK OK OK 3
|
||||
// 2 OK OK OK 1
|
||||
// 3 OK OK OK 1
|
||||
// 4 OK f_read 1 0x2 3 2 (20170424 fails, 20170522 OK)
|
||||
// 5 OK f_read 1 0x2 1
|
||||
// UM10503 recommendation: SAMPLE_DELAY=0x8, DRV_DELAY=0xF
|
||||
// Datasheet recommendation: SAMPLE_DELAY=0x9, DRV_DELAY=0xD
|
||||
LPC_SCU->SDDELAY =
|
||||
(0x8 << 0)
|
||||
| (0xf << 8)
|
||||
(0x0 << 0)
|
||||
| (0xa << 8) /* >6ns hold with low clk/dat/cmd output drive */
|
||||
;
|
||||
LPC_SDMMC->CTRL =
|
||||
(1U << 4) /* INT_ENABLE */
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
# FATFS files.
|
||||
FATFSSRC = ${CHIBIOS_PORTAPACK}/os/various/fatfs_bindings/fatfs_diskio.c \
|
||||
${CHIBIOS_PORTAPACK}/os/various/fatfs_bindings/fatfs_syscall.c \
|
||||
${CHIBIOS_PORTAPACK}/ext/fatfs/src/ff.c
|
||||
${CHIBIOS_PORTAPACK}/ext/fatfs/src/ff.c \
|
||||
${CHIBIOS_PORTAPACK}/ext/fatfs/src/option/unicode.c
|
||||
|
||||
FATFSINC = ${CHIBIOS_PORTAPACK}/ext/fatfs/src
|
||||
|
|
|
@ -2,6 +2,6 @@
|
|||
FATFSSRC = ${CHIBIOS}/os/various/fatfs_bindings/fatfs_diskio.c \
|
||||
${CHIBIOS}/os/various/fatfs_bindings/fatfs_syscall.c \
|
||||
${CHIBIOS}/ext/fatfs/src/ff.c \
|
||||
${CHIBIOS}/ext/fatfs/src/option/ccsbcs.c
|
||||
${CHIBIOS}/ext/fatfs/src/option/unicode.c
|
||||
|
||||
FATFSINC = ${CHIBIOS}/ext/fatfs/src
|
||||
|
|
|
@ -210,10 +210,11 @@ void AK4951::microphone_enable() {
|
|||
// map.r.digital_mic.DMIC = 0;
|
||||
// update(Register::DigitalMic);
|
||||
|
||||
map.r.signal_select_1.MGAIN20 = 0b110;
|
||||
const uint_fast8_t mgain = 0b0111;
|
||||
map.r.signal_select_1.MGAIN20 = mgain & 7;
|
||||
map.r.signal_select_1.PMMP = 1;
|
||||
map.r.signal_select_1.MPSEL = 1; // MPWR2 pin
|
||||
map.r.signal_select_1.MGAIN3 = 0b0;
|
||||
map.r.signal_select_1.MGAIN3 = (mgain >> 3) & 1;
|
||||
update(Register::SignalSelect1);
|
||||
|
||||
map.r.signal_select_2.INL = 0b01; // Lch input signal = LIN2
|
||||
|
|
100
firmware/common/backlight.cpp
Normal file
100
firmware/common/backlight.cpp
Normal file
|
@ -0,0 +1,100 @@
|
|||
/*
|
||||
* Copyright (C) 2017 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 "backlight.hpp"
|
||||
|
||||
#include "portapack_io.hpp"
|
||||
|
||||
namespace portapack {
|
||||
|
||||
void BacklightOnOff::on() {
|
||||
if( !is_on() ) {
|
||||
io.lcd_backlight(true);
|
||||
on_ = true;
|
||||
}
|
||||
}
|
||||
|
||||
void BacklightOnOff::off() {
|
||||
if( is_on() ) {
|
||||
io.lcd_backlight(false);
|
||||
on_ = false;
|
||||
}
|
||||
}
|
||||
|
||||
void BacklightCAT4004::set_level(const value_t value) {
|
||||
auto target = value;
|
||||
|
||||
// Clip target value to valid range.
|
||||
if( target < 0 ) {
|
||||
target = 0;
|
||||
}
|
||||
if( target > maximum_level ) {
|
||||
target = maximum_level;
|
||||
}
|
||||
|
||||
if( is_on() ) {
|
||||
pulses(target);
|
||||
} else {
|
||||
level_ = target;
|
||||
}
|
||||
}
|
||||
|
||||
void BacklightCAT4004::on() {
|
||||
if( !is_on() ) {
|
||||
io.lcd_backlight(true);
|
||||
halPolledDelay(ticks_setup);
|
||||
on_ = true;
|
||||
|
||||
// Just enabled driver, initial value is maximum.
|
||||
const auto target_level = level();
|
||||
level_ = maximum_level;
|
||||
|
||||
pulses(target_level);
|
||||
}
|
||||
}
|
||||
|
||||
void BacklightCAT4004::off() {
|
||||
if( is_on() ) {
|
||||
io.lcd_backlight(false);
|
||||
chThdSleepMilliseconds(ms_pwrdwn);
|
||||
on_ = false;
|
||||
}
|
||||
}
|
||||
|
||||
void BacklightCAT4004::pulses(value_t target) {
|
||||
while(level() != target) {
|
||||
pulse();
|
||||
}
|
||||
}
|
||||
|
||||
void BacklightCAT4004::pulse() {
|
||||
io.lcd_backlight(false);
|
||||
halPolledDelay(ticks_lo);
|
||||
io.lcd_backlight(true);
|
||||
halPolledDelay(ticks_hi);
|
||||
|
||||
level_ -= 1;
|
||||
if( level_ < 0 ) {
|
||||
level_ = levels() - 1;
|
||||
}
|
||||
}
|
||||
|
||||
} /* namespace portapack */
|
120
firmware/common/backlight.hpp
Normal file
120
firmware/common/backlight.hpp
Normal file
|
@ -0,0 +1,120 @@
|
|||
/*
|
||||
* Copyright (C) 2017 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.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
namespace portapack {
|
||||
|
||||
class Backlight {
|
||||
public:
|
||||
using value_t = int_fast8_t;
|
||||
|
||||
virtual ~Backlight() = default;
|
||||
|
||||
virtual value_t levels() const = 0;
|
||||
|
||||
virtual void set_level(const value_t value) = 0;
|
||||
virtual value_t level() const = 0;
|
||||
|
||||
virtual void increase() = 0;
|
||||
virtual void decrease() = 0;
|
||||
|
||||
virtual void on() = 0;
|
||||
virtual void off() = 0;
|
||||
|
||||
virtual bool is_on() const = 0;
|
||||
};
|
||||
|
||||
class BacklightBase : public Backlight {
|
||||
public:
|
||||
void increase() override {
|
||||
set_level(level() + 1);
|
||||
}
|
||||
|
||||
void decrease() override {
|
||||
set_level(level() - 1);
|
||||
}
|
||||
};
|
||||
|
||||
class BacklightOnOff : public BacklightBase {
|
||||
public:
|
||||
value_t levels() const override {
|
||||
return 1;
|
||||
}
|
||||
|
||||
void set_level(const value_t) override {
|
||||
}
|
||||
|
||||
value_t level() const override {
|
||||
return levels() - 1;
|
||||
}
|
||||
|
||||
void on() override;
|
||||
void off() override;
|
||||
|
||||
bool is_on() const override {
|
||||
return on_;
|
||||
}
|
||||
|
||||
private:
|
||||
static constexpr value_t maximum_level = 1;
|
||||
|
||||
bool on_ { false };
|
||||
};
|
||||
|
||||
class BacklightCAT4004 : public BacklightBase {
|
||||
public:
|
||||
value_t levels() const override {
|
||||
return maximum_level + 1;
|
||||
}
|
||||
|
||||
void set_level(const value_t value) override;
|
||||
|
||||
value_t level() const override {
|
||||
return level_;
|
||||
}
|
||||
|
||||
void on() override;
|
||||
void off() override;
|
||||
|
||||
bool is_on() const override {
|
||||
return on_;
|
||||
}
|
||||
|
||||
private:
|
||||
static constexpr value_t initial_brightness = 25;
|
||||
static constexpr value_t maximum_level = 31;
|
||||
|
||||
static constexpr uint32_t ticks_setup = 204e6 * 10e-6;
|
||||
static constexpr uint32_t ms_pwrdwn = 5;
|
||||
static constexpr uint32_t ticks_lo = 204e6 * 1e-6;
|
||||
static constexpr uint32_t ticks_hi = 204e6 * 1e-6;
|
||||
|
||||
value_t level_ { initial_brightness };
|
||||
bool on_ { false };
|
||||
|
||||
void pulses(value_t target);
|
||||
void pulse();
|
||||
};
|
||||
|
||||
} /* namespace portapack */
|
|
@ -99,6 +99,12 @@ public:
|
|||
shift_ir(static_cast<uint32_t>(instruction));
|
||||
}
|
||||
|
||||
void shift_dr(std::bitset<240>& value) {
|
||||
for(size_t i=0; i<value.size(); i++) {
|
||||
value[i] = shift_dr(1, value[i]);
|
||||
}
|
||||
}
|
||||
|
||||
private:
|
||||
jtag::JTAG& jtag;
|
||||
|
||||
|
@ -148,6 +154,10 @@ private:
|
|||
void shift_ir(const uint32_t value) {
|
||||
jtag.shift_ir(IR_LENGTH, value);
|
||||
}
|
||||
|
||||
uint32_t shift_dr(const size_t count, const uint32_t value) {
|
||||
return jtag.shift_dr(count, value);
|
||||
}
|
||||
};
|
||||
/*
|
||||
class ModeISP {
|
||||
|
|
|
@ -47,11 +47,17 @@ void lcd_reset() {
|
|||
|
||||
void lcd_sleep_in() {
|
||||
io.lcd_data_write_command_and_data(0x10, {});
|
||||
// "It will be necessary to wait 5msec before sending next command,
|
||||
// this is to allow time for the supply voltages and clock circuits
|
||||
// to stabilize."
|
||||
chThdSleepMilliseconds(5);
|
||||
}
|
||||
|
||||
void lcd_sleep_out() {
|
||||
io.lcd_data_write_command_and_data(0x11, {});
|
||||
// "It will be necessary to wait 120msec after sending Sleep Out
|
||||
// command (when in Sleep In Mode) before Sleep In command can be
|
||||
// sent."
|
||||
chThdSleepMilliseconds(120);
|
||||
}
|
||||
|
||||
|
@ -59,6 +65,20 @@ void lcd_display_on() {
|
|||
io.lcd_data_write_command_and_data(0x29, {});
|
||||
}
|
||||
|
||||
void lcd_display_off() {
|
||||
io.lcd_data_write_command_and_data(0x28, {});
|
||||
}
|
||||
|
||||
void lcd_sleep() {
|
||||
lcd_display_off();
|
||||
lcd_sleep_in();
|
||||
}
|
||||
|
||||
void lcd_wake() {
|
||||
lcd_sleep_out();
|
||||
lcd_display_on();
|
||||
}
|
||||
|
||||
void lcd_init() {
|
||||
// LCDs are configured for IM[2:0] = 001
|
||||
// 8080-I system, 16-bit parallel bus
|
||||
|
@ -165,8 +185,7 @@ void lcd_init() {
|
|||
0x47, 0x04, 0x0C, 0x0B, 0x29, 0x2F, 0x05
|
||||
});
|
||||
|
||||
lcd_sleep_out();
|
||||
lcd_display_on();
|
||||
lcd_wake();
|
||||
|
||||
// Turn on Tearing Effect Line (TE) output signal.
|
||||
io.lcd_data_write_command_and_data(0x35, { 0b00000000 });
|
||||
|
@ -255,21 +274,18 @@ void lcd_vertical_scrolling_start_address(
|
|||
void ILI9341::init() {
|
||||
lcd_reset();
|
||||
lcd_init();
|
||||
|
||||
io.lcd_backlight(1);
|
||||
}
|
||||
|
||||
void ILI9341::shutdown() {
|
||||
io.lcd_backlight(0);
|
||||
lcd_reset();
|
||||
}
|
||||
|
||||
void ILI9341::sleep() {
|
||||
lcd_sleep_in();
|
||||
lcd_sleep();
|
||||
}
|
||||
|
||||
void ILI9341::wake() {
|
||||
lcd_sleep_out();
|
||||
lcd_wake();
|
||||
}
|
||||
|
||||
void ILI9341::fill_rectangle(ui::Rect r, const ui::Color c) {
|
||||
|
|
|
@ -34,7 +34,7 @@ namespace lcd {
|
|||
class ILI9341 {
|
||||
public:
|
||||
constexpr ILI9341(
|
||||
) : scroll_state { 0, 0, 320, 0 }
|
||||
) : scroll_state { 0, 0, height(), 0 }
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -105,10 +105,10 @@ public:
|
|||
|
||||
private:
|
||||
struct scroll_t {
|
||||
uint16_t top_area;
|
||||
uint16_t bottom_area;
|
||||
uint16_t height;
|
||||
uint16_t current_position;
|
||||
ui::Coord top_area;
|
||||
ui::Coord bottom_area;
|
||||
ui::Dim height;
|
||||
ui::Coord current_position;
|
||||
};
|
||||
|
||||
scroll_t scroll_state;
|
||||
|
|
|
@ -49,13 +49,13 @@ constexpr Pin pins[] = {
|
|||
[P1_3] = { 1, 3, { .mode=5, .pd=0, .pu=0, .fast=0, .input=1, .ifilt=1 } }, /* SSP1_MISO/P41: MAX2837.DOUT(O) */
|
||||
[P1_4] = { 1, 4, { .mode=5, .pd=1, .pu=0, .fast=0, .input=0, .ifilt=1 } }, /* SSP1_MOSI/P40: MAX2837.DIN(I), MAX5864.DIN(I) */
|
||||
[P1_5] = { 1, 5, { .mode=0, .pd=0, .pu=1, .fast=0, .input=1, .ifilt=1 } }, /* SD_POW: PortaPack CPLD.TDO(O) */
|
||||
[P1_6] = { 1, 6, { .mode=7, .pd=0, .pu=1, .fast=1, .input=1, .ifilt=0 } }, /* SD_CMD: PortaPack SD.CMD(IO) */
|
||||
[P1_6] = { 1, 6, { .mode=7, .pd=0, .pu=1, .fast=0, .input=1, .ifilt=0 } }, /* SD_CMD: PortaPack SD.CMD(IO) */
|
||||
[P1_7] = { 1, 7, { .mode=0, .pd=1, .pu=0, .fast=0, .input=0, .ifilt=1 } }, /* !MIX_BYPASS/P35: U1.VCTL1(I), U11.VCTL2(I), U9.V2(I) */
|
||||
[P1_8] = { 1, 8, { .mode=0, .pd=0, .pu=1, .fast=0, .input=0, .ifilt=1 } }, /* SD_VOLT0: PortaPack CPLD.TMS(I) */
|
||||
[P1_9] = { 1, 9, { .mode=7, .pd=0, .pu=1, .fast=1, .input=1, .ifilt=0 } }, /* SD_DAT0: PortaPack SD.DAT0(IO) */
|
||||
[P1_10] = { 1, 10, { .mode=7, .pd=0, .pu=1, .fast=1, .input=1, .ifilt=0 } }, /* SD_DAT1: PortaPack SD.DAT1(IO) */
|
||||
[P1_11] = { 1, 11, { .mode=7, .pd=0, .pu=1, .fast=1, .input=1, .ifilt=0 } }, /* SD_DAT2: PortaPack SD.DAT2(IO) */
|
||||
[P1_12] = { 1, 12, { .mode=7, .pd=0, .pu=1, .fast=1, .input=1, .ifilt=0 } }, /* SD_DAT3: PortaPack SD.DAT3(IO) */
|
||||
[P1_9] = { 1, 9, { .mode=7, .pd=0, .pu=1, .fast=0, .input=1, .ifilt=0 } }, /* SD_DAT0: PortaPack SD.DAT0(IO) */
|
||||
[P1_10] = { 1, 10, { .mode=7, .pd=0, .pu=1, .fast=0, .input=1, .ifilt=0 } }, /* SD_DAT1: PortaPack SD.DAT1(IO) */
|
||||
[P1_11] = { 1, 11, { .mode=7, .pd=0, .pu=1, .fast=0, .input=1, .ifilt=0 } }, /* SD_DAT2: PortaPack SD.DAT2(IO) */
|
||||
[P1_12] = { 1, 12, { .mode=7, .pd=0, .pu=1, .fast=0, .input=1, .ifilt=0 } }, /* SD_DAT3: PortaPack SD.DAT3(IO) */
|
||||
[P1_13] = { 1, 13, { .mode=7, .pd=0, .pu=1, .fast=0, .input=1, .ifilt=1 } }, /* SD_CD: PortaPack SD.CD(O) */
|
||||
[P1_14] = { 1, 14, PinConfig::sgpio_out_fast_with_pullup(6) }, /* SGPIO10/P78/BANK2F3M8: CPLD.76/HOST_DISABLE(I) */
|
||||
[P1_15] = { 1, 15, PinConfig::sgpio_inout_fast(2) }, /* SGPIO2/BANK2F3M9: CPLD.74/HOST_DATA2(IO) */
|
||||
|
@ -64,20 +64,20 @@ constexpr Pin pins[] = {
|
|||
[P1_18] = { 1, 18, PinConfig::gpio_out_with_pulldown(0) }, /* SGPIO12/BANK2F3M12: CPLD.70/HOST_INVERT(I) */
|
||||
[P1_19] = { 1, 19, { .mode=1, .pd=1, .pu=0, .fast=0, .input=0, .ifilt=1 } }, /* SSP1_SCK/P39: MAX2837.SCLK(I), MAX5864.SCLK(I) */
|
||||
[P1_20] = { 1, 20, { .mode=0, .pd=0, .pu=1, .fast=0, .input=0, .ifilt=1 } }, /* CS_XCVR/P53: MAX2837.CS(I) */
|
||||
[P2_0] = { 2, 0, { .mode=4, .pd=0, .pu=1, .fast=0, .input=1, .ifilt=1 } }, /* U0_TXD: PortaPack P2_0/IO_STBX */
|
||||
[P2_1] = { 2, 1, { .mode=4, .pd=1, .pu=0, .fast=0, .input=1, .ifilt=1 } }, /* U0_RXD: PortaPack P2_1/ADDR */
|
||||
[P2_0] = { 2, 0, { .mode=4, .pd=0, .pu=0, .fast=0, .input=1, .ifilt=1 } }, /* U0_TXD: PortaPack P2_0/IO_STBX */
|
||||
[P2_1] = { 2, 1, { .mode=4, .pd=0, .pu=0, .fast=0, .input=1, .ifilt=1 } }, /* U0_RXD: PortaPack P2_1/ADDR */
|
||||
[P2_2] = { 2, 2, PinConfig::sgpio_inout_fast(0) }, /* SGPIO6/BANK2F3M16: CPLD.61/HOST_DATA6(IO) */
|
||||
[P2_3] = { 2, 3, { .mode=4, .pd=0, .pu=0, .fast=0, .input=1, .ifilt=1 } }, /* I2C1_SDA: PortaPack P2_3/LCD_TE */
|
||||
[P2_4] = { 2, 4, { .mode=4, .pd=0, .pu=0, .fast=0, .input=1, .ifilt=1 } }, /* I2C1_SCL: PortaPack P2_4/<unused> */
|
||||
[P2_4] = { 2, 4, { .mode=4, .pd=0, .pu=0, .fast=0, .input=1, .ifilt=1 } }, /* I2C1_SCL: PortaPack P2_4/LCD_RDX */
|
||||
[P2_5] = { 2, 5, { .mode=4, .pd=0, .pu=1, .fast=0, .input=0, .ifilt=1 } }, /* RX/P43: U7.VCTL1(I), U10.VCTL1(I), U2.VCTL1(I) */
|
||||
[P2_6] = { 2, 6, { .mode=4, .pd=0, .pu=0, .fast=0, .input=0, .ifilt=1 } }, /* MIXER_SCLK/P31: 33pF, RFFC5072.SCLK(I) */
|
||||
[P2_7] = { 2, 7, { .mode=0, .pd=0, .pu=0, .fast=0, .input=1, .ifilt=1 } }, /* ISP: 10K PU, Unused */
|
||||
[P2_8] = { 2, 8, { .mode=4, .pd=0, .pu=0, .fast=0, .input=0, .ifilt=1 } }, /* P2_8: 10K PD, BOOT2, DFU switch, PortaPack P2_8/LCD_RD */
|
||||
[P2_9] = { 2, 9, { .mode=0, .pd=0, .pu=0, .fast=0, .input=0, .ifilt=1 } }, /* P2_9: 10K PD, BOOT3, PortaPack P2_9/LCD_WR */
|
||||
[P2_8] = { 2, 8, { .mode=4, .pd=0, .pu=0, .fast=0, .input=0, .ifilt=1 } }, /* P2_8: 10K PD, BOOT2, DFU switch, PortaPack P2_8/<unused> */
|
||||
[P2_9] = { 2, 9, { .mode=0, .pd=0, .pu=0, .fast=0, .input=1, .ifilt=1 } }, /* P2_9: 10K PD, BOOT3, PortaPack P2_9/LCD_WRX */
|
||||
[P2_10] = { 2, 10, { .mode=0, .pd=0, .pu=1, .fast=0, .input=0, .ifilt=1 } }, /* AMP_BYPASS/P50: U14.V2(I), U12.V2(I) */
|
||||
[P2_11] = { 2, 11, { .mode=0, .pd=1, .pu=0, .fast=0, .input=0, .ifilt=1 } }, /* RX_AMP/P49: U12.V1(I), U14.V3(I) */
|
||||
[P2_12] = { 2, 12, { .mode=0, .pd=0, .pu=0, .fast=0, .input=0, .ifilt=1 } }, /* !RX_AMP_PWR/P52: 10K PU, Q1.G(I), power to U13 (RX amp) */
|
||||
[P2_13] = { 2, 13, { .mode=0, .pd=0, .pu=1, .fast=0, .input=1, .ifilt=1 } }, /* P2_13: PortaPack P2_13/DIR */
|
||||
[P2_13] = { 2, 13, { .mode=0, .pd=0, .pu=0, .fast=0, .input=1, .ifilt=1 } }, /* P2_13: PortaPack P2_13/DIR */
|
||||
[P3_0] = { 3, 0, { .mode=2, .pd=0, .pu=1, .fast=0, .input=0, .ifilt=1 } }, /* I2S0_TX_SCK: PortaPack I2S0_TX_SCK(I) */
|
||||
[P3_1] = { 3, 1, { .mode=0, .pd=0, .pu=1, .fast=0, .input=1, .ifilt=1 } }, /* I2S0_RX_WS: PortaPack I2S0_TX_WS(I). Input enabled to fold back into RX. */
|
||||
[P3_2] = { 3, 2, { .mode=0, .pd=0, .pu=1, .fast=0, .input=0, .ifilt=1 } }, /* I2S0_RX_SDA: PortaPack I2S0_TX_SDA(I) */
|
||||
|
@ -130,7 +130,7 @@ constexpr Pin pins[] = {
|
|||
[P9_5] = { 9, 5, { .mode=3, .pd=0, .pu=1, .fast=0, .input=1, .ifilt=1 } }, /* CPLD_TDO: CPLD.TDO(O) */
|
||||
[P9_6] = { 9, 6, PinConfig::sgpio_in_fast(6) }, /* SGPIO8/SGPIO_CLK/P60: SI5351C.CLK2(O) */
|
||||
[PF_4] = { 15, 4, { .mode=7, .pd=0, .pu=1, .fast=0, .input=0, .ifilt=1 } }, /* I2S0_RX_SCK: Unused */
|
||||
[CLK0] = { 24, 0, { .mode=4, .pd=1, .pu=0, .fast=1, .input=1, .ifilt=0 } }, /* SD_CLK: PortaPack SD.CLK, enable input buffer for timing feedback? */
|
||||
[CLK0] = { 24, 0, { .mode=4, .pd=1, .pu=0, .fast=0, .input=1, .ifilt=0 } }, /* SD_CLK: PortaPack SD.CLK, enable input buffer for timing feedback? */
|
||||
[CLK2] = { 24, 2, { .mode=6, .pd=1, .pu=0, .fast=0, .input=0, .ifilt=1 } }, /* I2S0_TX_CLK: PortaPack I2S0_TX_MCLK */
|
||||
};
|
||||
|
||||
|
|
|
@ -37,8 +37,8 @@ constexpr GPIO gpio_io_stbx = gpio[GPIO5_0]; /* P2_0 */
|
|||
constexpr GPIO gpio_addr = gpio[GPIO5_1]; /* P2_1 */
|
||||
constexpr GPIO gpio_lcd_te = gpio[GPIO5_3]; /* P2_3 */
|
||||
constexpr GPIO gpio_unused = gpio[GPIO5_7]; /* P2_8 */
|
||||
constexpr GPIO gpio_lcd_rd = gpio[GPIO5_4]; /* P2_4 */
|
||||
constexpr GPIO gpio_lcd_wr = gpio[GPIO1_10]; /* P2_9 */
|
||||
constexpr GPIO gpio_lcd_rdx = gpio[GPIO5_4]; /* P2_4 */
|
||||
constexpr GPIO gpio_lcd_wrx = gpio[GPIO1_10]; /* P2_9 */
|
||||
constexpr GPIO gpio_dir = gpio[GPIO1_13]; /* P2_13 */
|
||||
constexpr std::array<GPIO, 8> gpios_data {
|
||||
gpio[GPIO3_8],
|
||||
|
|
|
@ -43,8 +43,8 @@ void IO::init() {
|
|||
addr(0);
|
||||
|
||||
gpio_dir.output();
|
||||
gpio_lcd_rd.output();
|
||||
gpio_lcd_wr.output();
|
||||
gpio_lcd_rdx.output();
|
||||
gpio_lcd_wrx.output();
|
||||
gpio_io_stbx.output();
|
||||
gpio_addr.output();
|
||||
gpio_rot_a.input();
|
||||
|
@ -57,17 +57,11 @@ void IO::lcd_backlight(const bool value) {
|
|||
}
|
||||
|
||||
void IO::lcd_reset_state(const bool active) {
|
||||
/* NOTE: This overwrites the contents of the IO register, which for now
|
||||
* have no significance. But someday...?
|
||||
*/
|
||||
io_reg = (io_reg & 0xfe) | ((active ? 1 : 0) << 0);
|
||||
io_write(1, io_reg);
|
||||
}
|
||||
|
||||
void IO::audio_reset_state(const bool active) {
|
||||
/* Reset signal for audio codec. Some audio codecs (e.g. WM8731) do not
|
||||
* implement reset signal, only soft reset via I2C.
|
||||
*/
|
||||
/* NOTE: This overwrites the contents of the IO register, which for now
|
||||
* have no significance. But someday...?
|
||||
*/
|
||||
|
|
|
@ -80,15 +80,15 @@ public:
|
|||
|
||||
constexpr IO(
|
||||
GPIO gpio_dir,
|
||||
GPIO gpio_lcd_rd,
|
||||
GPIO gpio_lcd_wr,
|
||||
GPIO gpio_lcd_rdx,
|
||||
GPIO gpio_lcd_wrx,
|
||||
GPIO gpio_io_stbx,
|
||||
GPIO gpio_addr,
|
||||
GPIO gpio_rot_a,
|
||||
GPIO gpio_rot_b
|
||||
) : gpio_dir { gpio_dir },
|
||||
gpio_lcd_rd { gpio_lcd_rd },
|
||||
gpio_lcd_wr { gpio_lcd_wr },
|
||||
gpio_lcd_rdx { gpio_lcd_rdx },
|
||||
gpio_lcd_wrx { gpio_lcd_wrx },
|
||||
gpio_io_stbx { gpio_io_stbx },
|
||||
gpio_addr { gpio_addr },
|
||||
gpio_rot_a { gpio_rot_a },
|
||||
|
@ -102,13 +102,24 @@ public:
|
|||
void lcd_reset_state(const bool active);
|
||||
void audio_reset_state(const bool active);
|
||||
|
||||
void lcd_data_write_command_and_data(
|
||||
const uint_fast8_t command,
|
||||
const uint8_t* data,
|
||||
const size_t data_count
|
||||
) {
|
||||
lcd_command(command);
|
||||
for(size_t i=0; i<data_count; i++) {
|
||||
lcd_write_data(data[i]);
|
||||
}
|
||||
}
|
||||
|
||||
void lcd_data_write_command_and_data(
|
||||
const uint_fast8_t command,
|
||||
const std::initializer_list<uint8_t>& data
|
||||
) {
|
||||
lcd_command(command);
|
||||
for(const auto d : data) {
|
||||
lcd_write_data_fast(d);
|
||||
lcd_write_data(d);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -119,31 +130,31 @@ public:
|
|||
) {
|
||||
lcd_command(command);
|
||||
for(size_t i=0; i<data_count; i++) {
|
||||
data[i] = lcd_read_data_id();
|
||||
data[i] = lcd_read_data();
|
||||
}
|
||||
}
|
||||
|
||||
void lcd_write_word(const uint32_t w) {
|
||||
lcd_write_data_fast(w);
|
||||
lcd_write_data(w);
|
||||
}
|
||||
|
||||
void lcd_write_words(const uint16_t* const w, size_t n) {
|
||||
for(size_t i=0; i<n; i++) {
|
||||
lcd_write_data_fast(w[i]);
|
||||
lcd_write_data(w[i]);
|
||||
}
|
||||
}
|
||||
|
||||
void lcd_write_pixel(const ui::Color pixel) {
|
||||
lcd_write_data_fast(pixel.v);
|
||||
lcd_write_data(pixel.v);
|
||||
}
|
||||
|
||||
uint32_t lcd_read_word() {
|
||||
return lcd_read_data_frame_memory();
|
||||
return lcd_read_data();
|
||||
}
|
||||
|
||||
void lcd_write_pixels(const ui::Color pixel, size_t n) {
|
||||
while(n--) {
|
||||
lcd_write_data_fast(pixel.v);
|
||||
lcd_write_data(pixel.v);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -156,13 +167,13 @@ public:
|
|||
void lcd_read_bytes(uint8_t* byte, size_t byte_count) {
|
||||
size_t word_count = byte_count / 2;
|
||||
while(word_count) {
|
||||
const auto word = lcd_read_data_frame_memory();
|
||||
const auto word = lcd_read_data();
|
||||
*(byte++) = word >> 8;
|
||||
*(byte++) = word >> 0;
|
||||
word_count--;
|
||||
}
|
||||
if( byte_count & 1 ) {
|
||||
const auto word = lcd_read_data_frame_memory();
|
||||
const auto word = lcd_read_data();
|
||||
*(byte++) = word >> 8;
|
||||
}
|
||||
}
|
||||
|
@ -188,8 +199,8 @@ public:
|
|||
|
||||
private:
|
||||
const GPIO gpio_dir;
|
||||
const GPIO gpio_lcd_rd;
|
||||
const GPIO gpio_lcd_wr;
|
||||
const GPIO gpio_lcd_rdx;
|
||||
const GPIO gpio_lcd_wrx;
|
||||
const GPIO gpio_io_stbx;
|
||||
const GPIO gpio_addr;
|
||||
const GPIO gpio_rot_a;
|
||||
|
@ -202,19 +213,19 @@ private:
|
|||
uint8_t io_reg { 0x03 };
|
||||
|
||||
void lcd_rd_assert() {
|
||||
gpio_lcd_rd.set();
|
||||
gpio_lcd_rdx.clear();
|
||||
}
|
||||
|
||||
void lcd_rd_deassert() {
|
||||
gpio_lcd_rd.clear();
|
||||
gpio_lcd_rdx.set();
|
||||
}
|
||||
|
||||
void lcd_wr_assert() {
|
||||
gpio_lcd_wr.set();
|
||||
gpio_lcd_wrx.clear();
|
||||
}
|
||||
|
||||
void lcd_wr_deassert() {
|
||||
gpio_lcd_wr.clear();
|
||||
gpio_lcd_wrx.set();
|
||||
}
|
||||
|
||||
void io_stb_assert() {
|
||||
|
@ -287,7 +298,7 @@ private:
|
|||
addr(1); /* Set up for data phase (most likely after a command) */
|
||||
}
|
||||
|
||||
void lcd_write_data_fast(const uint32_t value) __attribute__((always_inline)) {
|
||||
void lcd_write_data(const uint32_t value) __attribute__((always_inline)) {
|
||||
// NOTE: Assumes and DIR=0 and ADDR=1 from command phase.
|
||||
data_write_high(value); /* Drive high byte */
|
||||
__asm__("nop");
|
||||
|
@ -300,42 +311,7 @@ private:
|
|||
lcd_wr_deassert(); /* Complete write operation */
|
||||
}
|
||||
|
||||
uint32_t lcd_read_data_id() {
|
||||
// NOTE: Assumes ADDR=1 from command phase.
|
||||
dir_read();
|
||||
|
||||
/* Start read operation */
|
||||
lcd_rd_assert();
|
||||
/* Wait for passthrough data(15:8) to settle -- ~16ns (3 cycles) typical */
|
||||
__asm__("nop");
|
||||
__asm__("nop");
|
||||
__asm__("nop");
|
||||
|
||||
__asm__("nop");
|
||||
__asm__("nop");
|
||||
__asm__("nop");
|
||||
__asm__("nop");
|
||||
const auto value_high = data_read();
|
||||
|
||||
/* Latch data[7:0] */
|
||||
lcd_rd_deassert();
|
||||
/* Wait for latched data[7:0] to settle -- ~26ns (5 cycles) typical */
|
||||
__asm__("nop");
|
||||
__asm__("nop");
|
||||
__asm__("nop");
|
||||
__asm__("nop");
|
||||
__asm__("nop");
|
||||
|
||||
__asm__("nop");
|
||||
__asm__("nop");
|
||||
__asm__("nop");
|
||||
__asm__("nop");
|
||||
|
||||
const auto value_low = data_read();
|
||||
return (value_high << 8) | value_low;
|
||||
}
|
||||
|
||||
uint32_t lcd_read_data_frame_memory() {
|
||||
uint32_t lcd_read_data() {
|
||||
// NOTE: Assumes ADDR=1 from command phase.
|
||||
dir_read();
|
||||
|
||||
|
|
File diff suppressed because it is too large
Load diff
Loading…
Add table
Add a link
Reference in a new issue