Merge remote-tracking branch 'upstream/master'

This commit is contained in:
furrtek 2017-07-25 00:20:57 +01:00
commit c2a9ed7d9b
46 changed files with 13951 additions and 12343 deletions

View File

@ -14,9 +14,9 @@ notifications:
- "Firmware download : https://portapack-h1-builds.s3.amazonaws.com/%{repository_slug}/%{build_number}/%{build_number}.1/build/firmware/portapack-h1-firmware-%{commit}.tar.bz2" - "Firmware download : https://portapack-h1-builds.s3.amazonaws.com/%{repository_slug}/%{build_number}/%{build_number}.1/build/firmware/portapack-h1-firmware-%{commit}.tar.bz2"
before_script: before_script:
- wget https://developer.arm.com/-/media/Files/downloads/gnu-rm/6-2016q4/gcc-arm-none-eabi-6_2-2016q4-20161216-linux.tar.bz2 -O /tmp/gcc-arm.tar.bz2 - wget https://developer.arm.com/-/media/Files/downloads/gnu-rm/6-2017q2/gcc-arm-none-eabi-6-2017-q2-update-linux.tar.bz2 -O /tmp/gcc-arm.tar.bz2
- tar -xf /tmp/gcc-arm.tar.bz2 - tar -xf /tmp/gcc-arm.tar.bz2
- export PATH=$PWD/gcc-arm-none-eabi-6_2-2016q4/bin:$PATH - export PATH=$PWD/gcc-arm-none-eabi-6-2017-q2-update/bin:$PATH
- export CC="arm-none-eabi-gcc" - export CC="arm-none-eabi-gcc"
- export CXX="arm-none-eabi-g++" - export CXX="arm-none-eabi-g++"

View File

@ -117,6 +117,7 @@ set(CPPSRC
${COMMON}/message_queue.cpp ${COMMON}/message_queue.cpp
${COMMON}/hackrf_hal.cpp ${COMMON}/hackrf_hal.cpp
portapack.cpp portapack.cpp
${COMMON}/backlight.cpp
${COMMON}/portapack_shared_memory.cpp ${COMMON}/portapack_shared_memory.cpp
baseband_api.cpp baseband_api.cpp
${COMMON}/portapack_persistent_memory.cpp ${COMMON}/portapack_persistent_memory.cpp

View File

@ -125,11 +125,12 @@ void EventDispatcher::set_display_sleep(const bool sleep) {
// TODO: Distribute display sleep message more broadly, shut down data generation // TODO: Distribute display sleep message more broadly, shut down data generation
// on baseband side, since all that data is being discarded during sleep. // on baseband side, since all that data is being discarded during sleep.
if( sleep ) { if( sleep ) {
portapack::io.lcd_backlight(false); portapack::backlight()->off();
portapack::display.sleep(); portapack::display.sleep();
} else { } else {
portapack::display.wake(); 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; EventDispatcher::display_sleep = sleep;
}; };
@ -284,6 +285,8 @@ void EventDispatcher::handle_lcd_frame_sync() {
DisplayFrameSyncMessage message; DisplayFrameSyncMessage message;
message_map.send(&message); message_map.send(&message);
painter.paint_widget_tree(top_widget); painter.paint_widget_tree(top_widget);
portapack::backlight()->on();
} }
void EventDispatcher::handle_switches() { void EventDispatcher::handle_switches() {

View File

@ -38,9 +38,13 @@
#include <cstdint> #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_SWITCHES = EVENT_MASK(3);
constexpr auto EVT_MASK_ENCODER = EVENT_MASK(4); constexpr auto EVT_MASK_ENCODER = EVENT_MASK(4);
constexpr auto EVT_MASK_TOUCH = EVENT_MASK(5); 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 { class EventDispatcher {
public: 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) { static inline void events_flag(const eventmask_t events) {
if( thread_event_loop ) { if( thread_event_loop ) {
chEvtSignal(thread_event_loop, events); chEvtSignal(thread_event_loop, events);
@ -92,11 +88,6 @@ public:
} }
private: 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; static Thread* thread_event_loop;
touch::Manager touch_manager { }; touch::Manager touch_manager { };

View File

@ -40,6 +40,8 @@
#include "hackrf_hal.hpp" #include "hackrf_hal.hpp"
using namespace hackrf::one; using namespace hackrf::one;
static Thread* thread_controls_event = NULL;
static std::array<Debounce, 7> switch_debounce; static std::array<Debounce, 7> switch_debounce;
static Encoder encoder; static Encoder encoder;
@ -156,7 +158,7 @@ void timer0_callback(GPTDriver* const) {
/* Signal event loop */ /* Signal event loop */
if( event_mask ) { if( event_mask ) {
chSysLockFromIsr(); chSysLockFromIsr();
EventDispatcher::events_flag_isr(event_mask); chEvtSignalI(thread_controls_event, event_mask);
chSysUnlockFromIsr(); chSysUnlockFromIsr();
} }
} }
@ -176,6 +178,8 @@ static GPTConfig timer0_config {
}; };
void controls_init() { void controls_init() {
thread_controls_event = chThdSelf();
touch::adc::start(); touch::adc::start();
/* GPT timer 0 is used to scan user interface controls -- touch screen, /* GPT timer 0 is used to scan user interface controls -- touch screen,

View File

@ -28,7 +28,10 @@
#include "portapack_hal.hpp" #include "portapack_hal.hpp"
static Thread* thread_lcd_frame_event = NULL;
static void pin_int4_interrupt_enable() { static void pin_int4_interrupt_enable() {
thread_lcd_frame_event = chThdSelf();
nvicEnableVector(PIN_INT4_IRQn, CORTEX_PRIORITY_MASK(LPC43XX_PIN_INT4_IRQ_PRIORITY)); 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(); CH_IRQ_PROLOGUE();
chSysLockFromIsr(); chSysLockFromIsr();
EventDispatcher::event_isr_lcd_frame_sync(); chEvtSignalI(thread_lcd_frame_event, EVT_MASK_LCD_FRAME_SYNC);
chSysUnlockFromIsr(); chSysUnlockFromIsr();
LPC_GPIO_INT->IST = (1U << 4); LPC_GPIO_INT->IST = (1U << 4);

View File

@ -27,8 +27,11 @@
using namespace lpc43xx; using namespace lpc43xx;
#include "event_m0.hpp" #include "event_m0.hpp"
static Thread* thread_rtc_event = NULL;
void rtc_interrupt_enable() { void rtc_interrupt_enable() {
thread_rtc_event = chThdSelf();
rtc::interrupt::enable_second_inc(); rtc::interrupt::enable_second_inc();
nvicEnableVector(RTC_IRQn, CORTEX_PRIORITY_MASK(LPC_RTC_IRQ_PRIORITY)); nvicEnableVector(RTC_IRQn, CORTEX_PRIORITY_MASK(LPC_RTC_IRQ_PRIORITY));
} }
@ -39,7 +42,7 @@ CH_IRQ_HANDLER(RTC_IRQHandler) {
CH_IRQ_PROLOGUE(); CH_IRQ_PROLOGUE();
chSysLockFromIsr(); chSysLockFromIsr();
EventDispatcher::event_isr_rtc_tick(); chEvtSignalI(thread_rtc_event, EVT_MASK_RTC_TICK);
chSysUnlockFromIsr(); chSysUnlockFromIsr();
rtc::interrupt::clear_all(); rtc::interrupt::clear_all();

View File

@ -38,13 +38,11 @@
#define LPC43XX_I2C_USE_I2C0 TRUE #define LPC43XX_I2C_USE_I2C0 TRUE
#define LPC43XX_I2C_USE_I2C1 TRUE
/* /*
* SPI driver system settings. * SPI driver system settings.
*/ */
#define LPC_SPI_USE_SSP0 TRUE
#define LPC_SPI_USE_SSP1 TRUE #define LPC_SPI_USE_SSP1 TRUE

View File

@ -31,6 +31,7 @@ using namespace hackrf::one;
#include "clock_manager.hpp" #include "clock_manager.hpp"
#include "backlight.hpp"
#include "touch_adc.hpp" #include "touch_adc.hpp"
#include "audio.hpp" #include "audio.hpp"
@ -48,18 +49,20 @@ namespace portapack {
portapack::IO io { portapack::IO io {
portapack::gpio_dir, portapack::gpio_dir,
portapack::gpio_lcd_rd, portapack::gpio_lcd_rdx,
portapack::gpio_lcd_wr, portapack::gpio_lcd_wrx,
portapack::gpio_io_stbx, portapack::gpio_io_stbx,
portapack::gpio_addr, portapack::gpio_addr,
portapack::gpio_lcd_te, portapack::gpio_lcd_te,
portapack::gpio_unused, portapack::gpio_unused,
}; };
portapack::BacklightCAT4004 backlight_cat4004;
portapack::BacklightOnOff backlight_on_off;
lcd::ILI9341 display; lcd::ILI9341 display;
I2C i2c0(&I2CD0); I2C i2c0(&I2CD0);
SPI ssp0(&SPID1);
SPI ssp1(&SPID2); SPI ssp1(&SPID2);
si5351::Si5351 clock_generator { 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() { static void shutdown_base() {
clock_manager.shutdown(); clock_manager.shutdown();
@ -162,6 +224,8 @@ static void shutdown_base() {
systick_stop(); systick_stop();
enable_unused_mcu_peripheral_clocks();
hackrf::one::reset(); hackrf::one::reset();
} }
@ -190,6 +254,10 @@ bool init() {
| (0U << 15) // SDA: Enable input glitch filter | (0U << 15) // SDA: Enable input glitch filter
; ;
disable_unused_mcu_peripheral_clocks();
LPC_CREG->CREG0 |= (1 << 5); // Disable USB0 PHY
power.init(); power.init();
gpio_max5864_select.set(); gpio_max5864_select.set();
@ -235,6 +303,7 @@ bool init() {
void shutdown() { void shutdown() {
gpdma::controller.disable(); gpdma::controller.disable();
backlight()->off();
display.shutdown(); display.shutdown();
radio::disable(); radio::disable();

View File

@ -19,6 +19,8 @@
* Boston, MA 02110-1301, USA. * Boston, MA 02110-1301, USA.
*/ */
#pragma once
#include "portapack_io.hpp" #include "portapack_io.hpp"
#include "receiver_model.hpp" #include "receiver_model.hpp"
@ -28,6 +30,7 @@
#include "spi_pp.hpp" #include "spi_pp.hpp"
#include "si5351.hpp" #include "si5351.hpp"
#include "lcd_ili9341.hpp" #include "lcd_ili9341.hpp"
#include "backlight.hpp"
#include "radio.hpp" #include "radio.hpp"
#include "clock_manager.hpp" #include "clock_manager.hpp"
@ -40,7 +43,6 @@ extern portapack::IO io;
extern lcd::ILI9341 display; extern lcd::ILI9341 display;
extern I2C i2c0; extern I2C i2c0;
extern SPI ssp0;
extern SPI ssp1; extern SPI ssp1;
extern si5351::Si5351 clock_generator; extern si5351::Si5351 clock_generator;
@ -56,4 +58,6 @@ extern TemperatureLogger temperature_logger;
bool init(); bool init();
void shutdown(); void shutdown();
Backlight* backlight();
} /* namespace portapack */ } /* namespace portapack */

View File

@ -586,10 +586,18 @@ void sdc_lld_start(SDCDriver *sdcp) {
sdio_reset(); sdio_reset();
sdio_reset_card(); 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 = LPC_SCU->SDDELAY =
(0x8 << 0) (0x0 << 0)
| (0xf << 8) | (0xa << 8) /* >6ns hold with low clk/dat/cmd output drive */
; ;
LPC_SDMMC->CTRL = LPC_SDMMC->CTRL =
(1U << 4) /* INT_ENABLE */ (1U << 4) /* INT_ENABLE */

View File

@ -1,6 +1,7 @@
# FATFS files. # FATFS files.
FATFSSRC = ${CHIBIOS_PORTAPACK}/os/various/fatfs_bindings/fatfs_diskio.c \ FATFSSRC = ${CHIBIOS_PORTAPACK}/os/various/fatfs_bindings/fatfs_diskio.c \
${CHIBIOS_PORTAPACK}/os/various/fatfs_bindings/fatfs_syscall.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 FATFSINC = ${CHIBIOS_PORTAPACK}/ext/fatfs/src

View File

@ -2,6 +2,6 @@
FATFSSRC = ${CHIBIOS}/os/various/fatfs_bindings/fatfs_diskio.c \ FATFSSRC = ${CHIBIOS}/os/various/fatfs_bindings/fatfs_diskio.c \
${CHIBIOS}/os/various/fatfs_bindings/fatfs_syscall.c \ ${CHIBIOS}/os/various/fatfs_bindings/fatfs_syscall.c \
${CHIBIOS}/ext/fatfs/src/ff.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 FATFSINC = ${CHIBIOS}/ext/fatfs/src

View File

@ -210,10 +210,11 @@ void AK4951::microphone_enable() {
// map.r.digital_mic.DMIC = 0; // map.r.digital_mic.DMIC = 0;
// update(Register::DigitalMic); // 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.PMMP = 1;
map.r.signal_select_1.MPSEL = 1; // MPWR2 pin 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); update(Register::SignalSelect1);
map.r.signal_select_2.INL = 0b01; // Lch input signal = LIN2 map.r.signal_select_2.INL = 0b01; // Lch input signal = LIN2

View 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 */

View 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 */

View File

@ -99,6 +99,12 @@ public:
shift_ir(static_cast<uint32_t>(instruction)); 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: private:
jtag::JTAG& jtag; jtag::JTAG& jtag;
@ -148,6 +154,10 @@ private:
void shift_ir(const uint32_t value) { void shift_ir(const uint32_t value) {
jtag.shift_ir(IR_LENGTH, 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 { class ModeISP {

View File

@ -47,11 +47,17 @@ void lcd_reset() {
void lcd_sleep_in() { void lcd_sleep_in() {
io.lcd_data_write_command_and_data(0x10, {}); 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); chThdSleepMilliseconds(5);
} }
void lcd_sleep_out() { void lcd_sleep_out() {
io.lcd_data_write_command_and_data(0x11, {}); 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); chThdSleepMilliseconds(120);
} }
@ -59,6 +65,20 @@ void lcd_display_on() {
io.lcd_data_write_command_and_data(0x29, {}); 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() { void lcd_init() {
// LCDs are configured for IM[2:0] = 001 // LCDs are configured for IM[2:0] = 001
// 8080-I system, 16-bit parallel bus // 8080-I system, 16-bit parallel bus
@ -165,8 +185,7 @@ void lcd_init() {
0x47, 0x04, 0x0C, 0x0B, 0x29, 0x2F, 0x05 0x47, 0x04, 0x0C, 0x0B, 0x29, 0x2F, 0x05
}); });
lcd_sleep_out(); lcd_wake();
lcd_display_on();
// Turn on Tearing Effect Line (TE) output signal. // Turn on Tearing Effect Line (TE) output signal.
io.lcd_data_write_command_and_data(0x35, { 0b00000000 }); io.lcd_data_write_command_and_data(0x35, { 0b00000000 });
@ -255,21 +274,18 @@ void lcd_vertical_scrolling_start_address(
void ILI9341::init() { void ILI9341::init() {
lcd_reset(); lcd_reset();
lcd_init(); lcd_init();
io.lcd_backlight(1);
} }
void ILI9341::shutdown() { void ILI9341::shutdown() {
io.lcd_backlight(0);
lcd_reset(); lcd_reset();
} }
void ILI9341::sleep() { void ILI9341::sleep() {
lcd_sleep_in(); lcd_sleep();
} }
void ILI9341::wake() { void ILI9341::wake() {
lcd_sleep_out(); lcd_wake();
} }
void ILI9341::fill_rectangle(ui::Rect r, const ui::Color c) { void ILI9341::fill_rectangle(ui::Rect r, const ui::Color c) {

View File

@ -34,7 +34,7 @@ namespace lcd {
class ILI9341 { class ILI9341 {
public: public:
constexpr ILI9341( constexpr ILI9341(
) : scroll_state { 0, 0, 320, 0 } ) : scroll_state { 0, 0, height(), 0 }
{ {
} }
@ -105,10 +105,10 @@ public:
private: private:
struct scroll_t { struct scroll_t {
uint16_t top_area; ui::Coord top_area;
uint16_t bottom_area; ui::Coord bottom_area;
uint16_t height; ui::Dim height;
uint16_t current_position; ui::Coord current_position;
}; };
scroll_t scroll_state; scroll_t scroll_state;

View File

@ -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_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_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_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_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_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_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=1, .input=1, .ifilt=0 } }, /* SD_DAT1: PortaPack SD.DAT1(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=1, .input=1, .ifilt=0 } }, /* SD_DAT2: PortaPack SD.DAT2(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=1, .input=1, .ifilt=0 } }, /* SD_DAT3: PortaPack SD.DAT3(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_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_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) */ [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_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_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) */ [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_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=1, .pu=0, .fast=0, .input=1, .ifilt=1 } }, /* U0_RXD: PortaPack P2_1/ADDR */ [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_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_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_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_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_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_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=0, .ifilt=1 } }, /* P2_9: 10K PD, BOOT3, PortaPack P2_9/LCD_WR */ [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_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_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_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_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_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) */ [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_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) */ [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 */ [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 */ [CLK2] = { 24, 2, { .mode=6, .pd=1, .pu=0, .fast=0, .input=0, .ifilt=1 } }, /* I2S0_TX_CLK: PortaPack I2S0_TX_MCLK */
}; };

View File

@ -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_addr = gpio[GPIO5_1]; /* P2_1 */
constexpr GPIO gpio_lcd_te = gpio[GPIO5_3]; /* P2_3 */ constexpr GPIO gpio_lcd_te = gpio[GPIO5_3]; /* P2_3 */
constexpr GPIO gpio_unused = gpio[GPIO5_7]; /* P2_8 */ constexpr GPIO gpio_unused = gpio[GPIO5_7]; /* P2_8 */
constexpr GPIO gpio_lcd_rd = gpio[GPIO5_4]; /* P2_4 */ constexpr GPIO gpio_lcd_rdx = gpio[GPIO5_4]; /* P2_4 */
constexpr GPIO gpio_lcd_wr = gpio[GPIO1_10]; /* P2_9 */ constexpr GPIO gpio_lcd_wrx = gpio[GPIO1_10]; /* P2_9 */
constexpr GPIO gpio_dir = gpio[GPIO1_13]; /* P2_13 */ constexpr GPIO gpio_dir = gpio[GPIO1_13]; /* P2_13 */
constexpr std::array<GPIO, 8> gpios_data { constexpr std::array<GPIO, 8> gpios_data {
gpio[GPIO3_8], gpio[GPIO3_8],

View File

@ -43,8 +43,8 @@ void IO::init() {
addr(0); addr(0);
gpio_dir.output(); gpio_dir.output();
gpio_lcd_rd.output(); gpio_lcd_rdx.output();
gpio_lcd_wr.output(); gpio_lcd_wrx.output();
gpio_io_stbx.output(); gpio_io_stbx.output();
gpio_addr.output(); gpio_addr.output();
gpio_rot_a.input(); gpio_rot_a.input();
@ -57,17 +57,11 @@ void IO::lcd_backlight(const bool value) {
} }
void IO::lcd_reset_state(const bool active) { 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_reg = (io_reg & 0xfe) | ((active ? 1 : 0) << 0);
io_write(1, io_reg); io_write(1, io_reg);
} }
void IO::audio_reset_state(const bool active) { 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 /* NOTE: This overwrites the contents of the IO register, which for now
* have no significance. But someday...? * have no significance. But someday...?
*/ */

View File

@ -80,15 +80,15 @@ public:
constexpr IO( constexpr IO(
GPIO gpio_dir, GPIO gpio_dir,
GPIO gpio_lcd_rd, GPIO gpio_lcd_rdx,
GPIO gpio_lcd_wr, GPIO gpio_lcd_wrx,
GPIO gpio_io_stbx, GPIO gpio_io_stbx,
GPIO gpio_addr, GPIO gpio_addr,
GPIO gpio_rot_a, GPIO gpio_rot_a,
GPIO gpio_rot_b GPIO gpio_rot_b
) : gpio_dir { gpio_dir }, ) : gpio_dir { gpio_dir },
gpio_lcd_rd { gpio_lcd_rd }, gpio_lcd_rdx { gpio_lcd_rdx },
gpio_lcd_wr { gpio_lcd_wr }, gpio_lcd_wrx { gpio_lcd_wrx },
gpio_io_stbx { gpio_io_stbx }, gpio_io_stbx { gpio_io_stbx },
gpio_addr { gpio_addr }, gpio_addr { gpio_addr },
gpio_rot_a { gpio_rot_a }, gpio_rot_a { gpio_rot_a },
@ -102,13 +102,24 @@ public:
void lcd_reset_state(const bool active); void lcd_reset_state(const bool active);
void audio_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( void lcd_data_write_command_and_data(
const uint_fast8_t command, const uint_fast8_t command,
const std::initializer_list<uint8_t>& data const std::initializer_list<uint8_t>& data
) { ) {
lcd_command(command); lcd_command(command);
for(const auto d : data) { for(const auto d : data) {
lcd_write_data_fast(d); lcd_write_data(d);
} }
} }
@ -119,31 +130,31 @@ public:
) { ) {
lcd_command(command); lcd_command(command);
for(size_t i=0; i<data_count; i++) { 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) { 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) { void lcd_write_words(const uint16_t* const w, size_t n) {
for(size_t i=0; i<n; i++) { 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) { void lcd_write_pixel(const ui::Color pixel) {
lcd_write_data_fast(pixel.v); lcd_write_data(pixel.v);
} }
uint32_t lcd_read_word() { 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) { void lcd_write_pixels(const ui::Color pixel, size_t n) {
while(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) { void lcd_read_bytes(uint8_t* byte, size_t byte_count) {
size_t word_count = byte_count / 2; size_t word_count = byte_count / 2;
while(word_count) { while(word_count) {
const auto word = lcd_read_data_frame_memory(); const auto word = lcd_read_data();
*(byte++) = word >> 8; *(byte++) = word >> 8;
*(byte++) = word >> 0; *(byte++) = word >> 0;
word_count--; word_count--;
} }
if( byte_count & 1 ) { if( byte_count & 1 ) {
const auto word = lcd_read_data_frame_memory(); const auto word = lcd_read_data();
*(byte++) = word >> 8; *(byte++) = word >> 8;
} }
} }
@ -188,8 +199,8 @@ public:
private: private:
const GPIO gpio_dir; const GPIO gpio_dir;
const GPIO gpio_lcd_rd; const GPIO gpio_lcd_rdx;
const GPIO gpio_lcd_wr; const GPIO gpio_lcd_wrx;
const GPIO gpio_io_stbx; const GPIO gpio_io_stbx;
const GPIO gpio_addr; const GPIO gpio_addr;
const GPIO gpio_rot_a; const GPIO gpio_rot_a;
@ -202,19 +213,19 @@ private:
uint8_t io_reg { 0x03 }; uint8_t io_reg { 0x03 };
void lcd_rd_assert() { void lcd_rd_assert() {
gpio_lcd_rd.set(); gpio_lcd_rdx.clear();
} }
void lcd_rd_deassert() { void lcd_rd_deassert() {
gpio_lcd_rd.clear(); gpio_lcd_rdx.set();
} }
void lcd_wr_assert() { void lcd_wr_assert() {
gpio_lcd_wr.set(); gpio_lcd_wrx.clear();
} }
void lcd_wr_deassert() { void lcd_wr_deassert() {
gpio_lcd_wr.clear(); gpio_lcd_wrx.set();
} }
void io_stb_assert() { void io_stb_assert() {
@ -287,7 +298,7 @@ private:
addr(1); /* Set up for data phase (most likely after a command) */ 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. // NOTE: Assumes and DIR=0 and ADDR=1 from command phase.
data_write_high(value); /* Drive high byte */ data_write_high(value); /* Drive high byte */
__asm__("nop"); __asm__("nop");
@ -300,42 +311,7 @@ private:
lcd_wr_deassert(); /* Complete write operation */ lcd_wr_deassert(); /* Complete write operation */
} }
uint32_t lcd_read_data_id() { uint32_t lcd_read_data() {
// 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() {
// NOTE: Assumes ADDR=1 from command phase. // NOTE: Assumes ADDR=1 from command phase.
dir_read(); dir_read();

File diff suppressed because it is too large Load Diff

View File

@ -4,7 +4,7 @@ software-defined radio (SDR).
Schematic Schematic
========= =========
The schematic was drawn using KiCad. The schematic was drawn using KiCad 4.0.6.
Schematic symbols are cached in the design files, but are also Schematic symbols are cached in the design files, but are also
available in a separate repository: available in a separate repository:
@ -35,7 +35,7 @@ the JTAG pins from the HackRF One's microcontroller.
License License
======= =======
Copyright (C) 2013, 2014, 2015 Jared Boone, ShareBrained Technology, Inc. Copyright (C) 2013-2017 Jared Boone, ShareBrained Technology, Inc.
These files are part of PortaPack. These files are part of PortaPack.

File diff suppressed because it is too large Load Diff

View File

@ -7,7 +7,7 @@ pcb_hole_pad_r = 5.6 / 2;
h1_pcb_thickness = 1.64; h1_pcb_thickness = 1.64;
pp_h1_pcb_thickness = 1.56; pp_h1_pcb_thickness = 1.56;
spacer_height = 0.5 * 25.4; spacer_height = 12.0;
bolt_drill_d = 3.0; bolt_drill_d = 3.0;
pcb_attach_drills_depth = 4.0; pcb_attach_drills_depth = 4.0;
@ -17,7 +17,17 @@ case_thickness = 1.5;
case_bottom_thickness = case_thickness * 2; case_bottom_thickness = case_thickness * 2;
h1_pcb_bottom_clearance = 4.0; h1_pcb_bottom_clearance = 4.0;
case_bottom_tool_r = 3.0; case_bottom_tool_r = 3.0;
case_lid_thickness = 0.125 * 25.4;
h1_led_hole_diameter = 2;
h1_led_diffuser_thickness = 0.85;
case_pcb_n_clearance = h1_led_diffuser_thickness + 0.15;
case_pcb_w_clearance = pcb_case_clearance;
case_pcb_e_clearance = pcb_case_clearance;
case_pcb_s_clearance = pcb_case_clearance;
lcd_thickness = 3.8;
case_lid_thickness = 3.0 / 16.0 * 25.4;
case_height_above_datum = h1_pcb_thickness + spacer_height + pp_h1_pcb_thickness + case_lid_thickness; case_height_above_datum = h1_pcb_thickness + spacer_height + pp_h1_pcb_thickness + case_lid_thickness;
case_height_below_datum = case_bottom_thickness + h1_pcb_bottom_clearance; case_height_below_datum = case_bottom_thickness + h1_pcb_bottom_clearance;
@ -27,19 +37,17 @@ attach_foot_r = pcb_hole_pad_r;
attach_drill_r = bolt_drill_d / 2.0; attach_drill_r = bolt_drill_d / 2.0;
case_bumper_d = 0.5 * 25.4; case_bumper_d = 0.5 * 25.4;
case_bumper_clearance = 0.5; case_bumper_clearance = 0.0;
case_bumper_emboss_depth = 1.0; case_bumper_emboss_depth = 1.0;
case_radiused = true; case_radiused = true;
case_bumper_inset_from_pcb_edge = case_radiused ? 10.0 : 8.0; case_bumper_inset_from_pcb_edge = case_radiused ? 14.0 : 12.0;
mounting_drills = [ mounting_drills = [
[4, 4], [4, 4],
[66, pcb_w - 4],
[116, 4], [116, 4],
[4, pcb_w - 4], [4, pcb_w - 4],
[71, pcb_w - 44],
[116, pcb_w - 4] [116, pcb_w - 4]
]; ];
@ -58,7 +66,14 @@ module pcb_outline() {
module pcb_outline_clearance() { module pcb_outline_clearance() {
minkowski() { minkowski() {
pcb_outline(); offset(r=-pcb_corner_r) {
circle(r=pcb_case_clearance); polygon([
[0 - case_pcb_n_clearance, 0 - case_pcb_w_clearance],
[0 - case_pcb_n_clearance, pcb_w + case_pcb_e_clearance],
[pcb_l + case_pcb_s_clearance, pcb_w + case_pcb_e_clearance],
[pcb_l + case_pcb_s_clearance, 0 - case_pcb_w_clearance]
]);
}
circle(r=pcb_corner_r);
} }
} }

View File

@ -18,11 +18,9 @@ module attach_center() {
module pcb_supports() { module pcb_supports() {
translate(mounting_drills[0]) attach_corner(); translate(mounting_drills[0]) attach_corner();
translate(mounting_drills[1]) rotate(90) attach_side(); translate(mounting_drills[1]) rotate(90) attach_corner();
translate(mounting_drills[2]) rotate(90) attach_corner(); translate(mounting_drills[2]) rotate(270) attach_corner();
translate(mounting_drills[3]) rotate(270) attach_corner(); translate(mounting_drills[3]) rotate(180) attach_corner();
translate(mounting_drills[4]) attach_center();
translate(mounting_drills[5]) rotate(180) attach_corner();
} }
module pcb_attach_drill_outline() { module pcb_attach_drill_outline() {

View File

@ -227,11 +227,9 @@ module led(refdes, c) {
} }
module led_drill() { module led_drill() {
hole_diameter = 2;
translate([0, -0.25, -0.3]) { translate([0, -0.25, -0.3]) {
rotate([90, 0, 0]) { rotate([90, 0, 0]) {
cylinder(d=hole_diameter, h=10); cylinder(d=h1_led_hole_diameter, h=10);
} }
} }
} }
@ -712,7 +710,6 @@ module micro_sd_drill(clearance) {
module portapack_h1_pcb_mounting_hole_drills() { module portapack_h1_pcb_mounting_hole_drills() {
translate([ 64, 104]) pcb_mounting_hole_drill(); translate([ 64, 104]) pcb_mounting_hole_drill();
translate([126, 104]) pcb_mounting_hole_drill();
translate([176, 104]) pcb_mounting_hole_drill(); translate([176, 104]) pcb_mounting_hole_drill();
translate([ 64, 171]) pcb_mounting_hole_drill(); translate([ 64, 171]) pcb_mounting_hole_drill();
translate([176, 171]) pcb_mounting_hole_drill(); translate([176, 171]) pcb_mounting_hole_drill();
@ -810,7 +807,6 @@ module portapack_h1_stack_hackrf_one() {
module portapack_h1_stack_spacers() { module portapack_h1_stack_spacers() {
hackrf_one_transform() { hackrf_one_transform() {
translate([ 64, 104]) spacer(); translate([ 64, 104]) spacer();
translate([126, 104]) spacer();
translate([176, 104]) spacer(); translate([176, 104]) spacer();
translate([ 64, 171]) spacer(); translate([ 64, 171]) spacer();
translate([176, 171]) spacer(); translate([176, 171]) spacer();
@ -825,7 +821,6 @@ module portapack_h1_stack_screws() {
screw_tz = spacer_height + pp_h1_pcb_thickness; screw_tz = spacer_height + pp_h1_pcb_thickness;
translate([0, 0, screw_tz]) portapack_h1_transform() { translate([0, 0, screw_tz]) portapack_h1_transform() {
translate([ 64, 104]) screw(); translate([ 64, 104]) screw();
translate([126, 104]) screw();
translate([176, 104]) screw(); translate([176, 104]) screw();
translate([ 64, 171]) screw(); translate([ 64, 171]) screw();
translate([176, 171]) screw(); translate([176, 171]) screw();

View File

@ -259,7 +259,6 @@ set_location_assignment PIN_4 -to LCD_BACKLIGHT
set_instance_assignment -name IO_STANDARD "3.3-V LVCMOS" -to LCD_BACKLIGHT set_instance_assignment -name IO_STANDARD "3.3-V LVCMOS" -to LCD_BACKLIGHT
set_instance_assignment -name CURRENT_STRENGTH_NEW "MINIMUM CURRENT" -to LCD_BACKLIGHT set_instance_assignment -name CURRENT_STRENGTH_NEW "MINIMUM CURRENT" -to LCD_BACKLIGHT
set_instance_assignment -name SLOW_SLEW_RATE ON -to LCD_BACKLIGHT set_instance_assignment -name SLOW_SLEW_RATE ON -to LCD_BACKLIGHT
set_instance_assignment -name PCI_IO OFF -to LCD_BACKLIGHT
set_location_assignment PIN_30 -to MCU_LCD_RD set_location_assignment PIN_30 -to MCU_LCD_RD
set_instance_assignment -name IO_STANDARD "3.3-V LVCMOS" -to MCU_LCD_RD set_instance_assignment -name IO_STANDARD "3.3-V LVCMOS" -to MCU_LCD_RD
set_instance_assignment -name CURRENT_STRENGTH_NEW "MINIMUM CURRENT" -to MCU_LCD_RD set_instance_assignment -name CURRENT_STRENGTH_NEW "MINIMUM CURRENT" -to MCU_LCD_RD
@ -287,3 +286,34 @@ set_instance_assignment -name CURRENT_STRENGTH_NEW "MINIMUM CURRENT" -to MCU_P2_
set_instance_assignment -name SLOW_SLEW_RATE ON -to MCU_P2_8 set_instance_assignment -name SLOW_SLEW_RATE ON -to MCU_P2_8
set_instance_assignment -name PCI_IO OFF -to MCU_P2_8 set_instance_assignment -name PCI_IO OFF -to MCU_P2_8
set_global_assignment -name NUM_PARALLEL_PROCESSORS ALL set_global_assignment -name NUM_PARALLEL_PROCESSORS ALL
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[15]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[14]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[13]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[12]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[11]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[10]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[9]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[8]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[7]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[6]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[5]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[4]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[3]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[2]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[1]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[0]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[7]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[6]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[5]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[4]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[3]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[2]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[1]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[0]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_ADDR
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_DIR
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_IO_STBX
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_LCD_RD
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_LCD_WR
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_P2_8

View File

@ -45,7 +45,7 @@ set lcd_data_wr_hold 10.0
# Create Clock # Create Clock
#************************************************************** #**************************************************************
create_clock -name {MCU_STROBE} -period 66.000 -waveform { 0.000 33.000 } [get_ports {MCU_STROBE}] create_clock -name {MCU_LCD_WRX} -period 66.000 -waveform { 0.000 33.000 } [get_ports {MCU_LCD_WRX}]
#create_clock -name strobe_virt -period 66.000 #create_clock -name strobe_virt -period 66.000
#************************************************************** #**************************************************************
@ -88,8 +88,8 @@ create_clock -name {MCU_STROBE} -period 66.000 -waveform { 0.000 33.000 } [get_p
# Set False Path # Set False Path
#************************************************************** #**************************************************************
set_false_path -from [get_clocks {MCU_STROBE}] -to [get_ports {TP_D TP_L TP_R TP_U}] #set_false_path -from [get_clocks {MCU_IO_STBX}] -to [get_ports {TP_D TP_L TP_R TP_U}]
set_false_path -from [get_ports {SW_D SW_L SW_R SW_ROT_A SW_ROT_B SW_SEL SW_U}] -to [get_ports {MCU_D[*]}] #set_false_path -from [get_ports {SW_D SW_L SW_R SW_ROT_A SW_ROT_B SW_SEL SW_U}] -to [get_ports {MCU_D[*]}]
#************************************************************** #**************************************************************

View File

@ -26,11 +26,11 @@ entity top is
MCU_D : inout std_logic_vector(7 downto 0); MCU_D : inout std_logic_vector(7 downto 0);
MCU_DIR : in std_logic; MCU_DIR : in std_logic;
MCU_IO_STBX : in std_logic; MCU_IO_STBX : in std_logic;
MCU_LCD_WR : in std_logic; MCU_LCD_WRX : in std_logic;
MCU_ADDR : in std_logic; MCU_ADDR : in std_logic;
MCU_LCD_TE : out std_logic; MCU_LCD_TE : out std_logic;
MCU_P2_8 : in std_logic; MCU_P2_8 : in std_logic;
MCU_LCD_RD : in std_logic; MCU_LCD_RDX : in std_logic;
TP_U : out std_logic; TP_U : out std_logic;
TP_D : out std_logic; TP_D : out std_logic;
@ -112,13 +112,13 @@ begin
io_strobe <= (MCU_IO_STBX = '0'); io_strobe <= (MCU_IO_STBX = '0');
io_read_strobe <= io_strobe and dir_read; io_read_strobe <= io_strobe and dir_read;
lcd_read_strobe <= (MCU_LCD_RD = '1'); lcd_read_strobe <= (MCU_LCD_RDX = '0');
lcd_write <= not lcd_read_strobe; lcd_write <= not lcd_read_strobe;
-- LCD interface -- LCD interface
LCD_RS <= MCU_ADDR; LCD_RS <= MCU_ADDR;
LCD_RDX <= not MCU_LCD_RD; LCD_RDX <= MCU_LCD_RDX;
LCD_WRX <= not MCU_LCD_WR; LCD_WRX <= MCU_LCD_WRX;
lcd_data_out <= lcd_data_out_q & mcu_data_in; lcd_data_out <= lcd_data_out_q & mcu_data_in;
lcd_data_in <= LCD_DB; lcd_data_in <= LCD_DB;
@ -136,17 +136,17 @@ begin
-- Synchronous behaviors: -- Synchronous behaviors:
-- LCD write: Capture LCD high byte on LCD_WRX falling edge. -- LCD write: Capture LCD high byte on LCD_WRX falling edge.
process(MCU_LCD_WR, mcu_data_in) process(MCU_LCD_WRX, mcu_data_in)
begin begin
if rising_edge(MCU_LCD_WR) then if falling_edge(MCU_LCD_WRX) then
lcd_data_out_q <= mcu_data_in; lcd_data_out_q <= mcu_data_in;
end if; end if;
end process; end process;
-- LCD read: Capture LCD low byte on LCD_RD falling edge. -- LCD read: Capture LCD low byte on LCD_RD falling edge.
process(MCU_LCD_RD, lcd_data_in) process(MCU_LCD_RDX, lcd_data_in)
begin begin
if falling_edge(MCU_LCD_RD) then if rising_edge(MCU_LCD_RDX) then
lcd_data_in_q <= lcd_data_in(7 downto 0); lcd_data_in_q <= lcd_data_in(7 downto 0);
end if; end if;
end process; end process;

View File

@ -290,3 +290,34 @@ set_instance_assignment -name CURRENT_STRENGTH_NEW "MINIMUM CURRENT" -to MCU_P2_
set_instance_assignment -name SLOW_SLEW_RATE ON -to MCU_P2_8 set_instance_assignment -name SLOW_SLEW_RATE ON -to MCU_P2_8
set_instance_assignment -name PCI_IO OFF -to MCU_P2_8 set_instance_assignment -name PCI_IO OFF -to MCU_P2_8
set_global_assignment -name NUM_PARALLEL_PROCESSORS ALL set_global_assignment -name NUM_PARALLEL_PROCESSORS ALL
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[15]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[14]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[13]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[12]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[11]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[10]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[9]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[8]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[7]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[6]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[5]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[4]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[3]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[2]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[1]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to LCD_DB[0]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[7]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[6]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[5]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[4]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[3]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[2]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[1]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_D[0]
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_ADDR
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_DIR
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_IO_STBX
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_LCD_RD
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_LCD_WR
set_instance_assignment -name WEAK_PULL_UP_RESISTOR ON -to MCU_P2_8

View File

@ -45,7 +45,7 @@ set lcd_data_wr_hold 10.0
# Create Clock # Create Clock
#************************************************************** #**************************************************************
create_clock -name {MCU_LCD_WR} -period 66.000 -waveform { 0.000 33.000 } [get_ports {MCU_LCD_WR}] create_clock -name {MCU_LCD_WRX} -period 66.000 -waveform { 0.000 33.000 } [get_ports {MCU_LCD_WRX}]
#create_clock -name strobe_virt -period 66.000 #create_clock -name strobe_virt -period 66.000
#************************************************************** #**************************************************************

View File

@ -26,11 +26,11 @@ entity top is
MCU_D : inout std_logic_vector(7 downto 0); MCU_D : inout std_logic_vector(7 downto 0);
MCU_DIR : in std_logic; MCU_DIR : in std_logic;
MCU_IO_STBX : in std_logic; MCU_IO_STBX : in std_logic;
MCU_LCD_WR : in std_logic; MCU_LCD_WRX : in std_logic;
MCU_ADDR : in std_logic; MCU_ADDR : in std_logic;
MCU_LCD_TE : out std_logic; MCU_LCD_TE : out std_logic;
MCU_P2_8 : in std_logic; MCU_P2_8 : in std_logic;
MCU_LCD_RD : in std_logic; MCU_LCD_RDX : in std_logic;
TP_U : out std_logic; TP_U : out std_logic;
TP_D : out std_logic; TP_D : out std_logic;
@ -116,13 +116,13 @@ begin
io_strobe <= (MCU_IO_STBX = '0'); io_strobe <= (MCU_IO_STBX = '0');
io_read_strobe <= io_strobe and dir_read; io_read_strobe <= io_strobe and dir_read;
lcd_read_strobe <= (MCU_LCD_RD = '1'); lcd_read_strobe <= (MCU_LCD_RDX = '0');
lcd_write <= not lcd_read_strobe; lcd_write <= not lcd_read_strobe;
-- LCD interface -- LCD interface
LCD_RS <= MCU_ADDR; LCD_RS <= MCU_ADDR;
LCD_RDX <= not MCU_LCD_RD; LCD_RDX <= MCU_LCD_RDX;
LCD_WRX <= not MCU_LCD_WR; LCD_WRX <= MCU_LCD_WRX;
lcd_data_out <= lcd_data_out_q & mcu_data_in; lcd_data_out <= lcd_data_out_q & mcu_data_in;
lcd_data_in <= LCD_DB; lcd_data_in <= LCD_DB;
@ -141,17 +141,17 @@ begin
-- Synchronous behaviors: -- Synchronous behaviors:
-- LCD write: Capture LCD high byte on LCD_WRX falling edge. -- LCD write: Capture LCD high byte on LCD_WRX falling edge.
process(MCU_LCD_WR, mcu_data_in) process(MCU_LCD_WRX, mcu_data_in)
begin begin
if rising_edge(MCU_LCD_WR) then if falling_edge(MCU_LCD_WRX) then
lcd_data_out_q <= mcu_data_in; lcd_data_out_q <= mcu_data_in;
end if; end if;
end process; end process;
-- LCD read: Capture LCD low byte on LCD_RD falling edge. -- LCD read: Capture LCD low byte on LCD_RD falling edge.
process(MCU_LCD_RD, lcd_data_in) process(MCU_LCD_RDX, lcd_data_in)
begin begin
if falling_edge(MCU_LCD_RD) then if rising_edge(MCU_LCD_RDX) then
lcd_data_in_q <= lcd_data_in(7 downto 0); lcd_data_in_q <= lcd_data_in(7 downto 0);
end if; end if;
end process; end process;

View File

@ -0,0 +1,25 @@
(fp_lib_table
(lib (name alps)(type KiCad)(uri ${KISBLIB}/alps.pretty)(options "")(descr ""))
(lib (name bat_coin)(type KiCad)(uri ${KISBLIB}/bat_coin.pretty)(options "")(descr ""))
(lib (name ck)(type KiCad)(uri ${KISBLIB}/ck.pretty)(options "")(descr ""))
(lib (name cui)(type KiCad)(uri ${KISBLIB}/cui.pretty)(options "")(descr ""))
(lib (name eastrising)(type KiCad)(uri ${KISBLIB}/eastrising.pretty)(options "")(descr ""))
(lib (name fiducial)(type KiCad)(uri ${KISBLIB}/fiducial.pretty)(options "")(descr ""))
(lib (name header)(type KiCad)(uri ${KISBLIB}/header.pretty)(options "")(descr ""))
(lib (name hole)(type KiCad)(uri ${KISBLIB}/hole.pretty)(options "")(descr ""))
(lib (name ipc_capae)(type KiCad)(uri ${KISBLIB}/ipc_capae.pretty)(options "")(descr ""))
(lib (name ipc_capc)(type KiCad)(uri ${KISBLIB}/ipc_capc.pretty)(options "")(descr ""))
(lib (name ipc_indc)(type KiCad)(uri ${KISBLIB}/ipc_indc.pretty)(options "")(descr ""))
(lib (name ipc_qfn)(type KiCad)(uri ${KISBLIB}/ipc_qfn.pretty)(options "")(descr ""))
(lib (name ipc_qfp)(type KiCad)(uri ${KISBLIB}/ipc_qfp.pretty)(options "")(descr ""))
(lib (name ipc_resc)(type KiCad)(uri ${KISBLIB}/ipc_resc.pretty)(options "")(descr ""))
(lib (name ipc_son)(type KiCad)(uri ${KISBLIB}/ipc_son.pretty)(options "")(descr ""))
(lib (name ipc_sop)(type KiCad)(uri ${KISBLIB}/ipc_sop.pretty)(options "")(descr ""))
(lib (name ipc_sot)(type KiCad)(uri ${KISBLIB}/ipc_sot.pretty)(options "")(descr ""))
(lib (name jst)(type KiCad)(uri ${KISBLIB}/jst.pretty)(options "")(descr ""))
(lib (name molex)(type KiCad)(uri ${KISBLIB}/molex.pretty)(options "")(descr ""))
(lib (name on_semi)(type KiCad)(uri ${KISBLIB}/on_semi.pretty)(options "")(descr ""))
(lib (name tp)(type KiCad)(uri ${KISBLIB}/tp.pretty)(options "")(descr ""))
(lib (name ipc_ledc)(type KiCad)(uri ${KISBLIB}/ipc_ledc.pretty)(options "")(descr ""))
(lib (name sharebrained)(type KiCad)(uri ${KISBLIB}/sharebrained.pretty)(options "")(descr ""))
)

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -1,4 +1,4 @@
update=Wednesday, July 15, 2015 'PMt' 10:20:27 PM update=Mon 19 Jun 2017 03:56:47 PM PDT
version=1 version=1
last_client=kicad last_client=kicad
[cvpcb] [cvpcb]
@ -6,65 +6,58 @@ version=1
NetIExt=net NetIExt=net
[cvpcb/libraries] [cvpcb/libraries]
EquName1=devcms EquName1=devcms
[pcbnew]
version=1
LastNetListRead=
UseCmpFile=1
PadDrill=0.600000000000
PadDrillOvalY=0.600000000000
PadSizeH=1.500000000000
PadSizeV=1.500000000000
PcbTextSizeV=1.500000000000
PcbTextSizeH=1.500000000000
PcbTextThickness=0.300000000000
ModuleTextSizeV=1.000000000000
ModuleTextSizeH=1.000000000000
ModuleTextSizeThickness=0.150000000000
SolderMaskClearance=0.000000000000
SolderMaskMinWidth=0.000000000000
DrawSegmentWidth=0.200000000000
BoardOutlineThickness=0.100000000000
ModuleOutlineThickness=0.150000000000
[pcbnew/libraries]
LibDir=../../../library-kicad
LibName1=sockets
LibName2=connect
LibName3=discret
LibName4=pin_array
LibName5=divers
LibName6=smd_capacitors
LibName7=smd_resistors
LibName8=smd_crystal&oscillator
LibName9=smd_dil
LibName10=smd_transistors
LibName11=libcms
LibName12=display
LibName13=led
LibName14=dip_sockets
LibName15=pga_sockets
LibName16=valves
[general] [general]
version=1 version=1
[eeschema] [eeschema]
version=1 version=1
LibDir=../../../library-kicad LibDir=../../../library-kicad
[eeschema/libraries] [eeschema/libraries]
LibName1=hackrf_expansion LibName1=portapack_h1-rescue
LibName2=wolfson LibName2=hackrf_expansion
LibName3=passive LibName3=passive
LibName4=lcd_kingtech LibName4=supply
LibName5=supply LibName5=trs_jack
LibName6=io_expander LibName6=battery
LibName7=trs_jack LibName7=sd
LibName8=battery LibName8=ck
LibName9=mosfet LibName9=altera
LibName10=microphone LibName10=regulator
LibName11=sd LibName11=tp
LibName12=ck LibName12=header
LibName13=altera LibName13=hole
LibName14=regulator LibName14=sharebrained
LibName15=tp LibName15=fiducial
LibName16=header LibName16=eastrising
LibName17=hole LibName17=on_semi
LibName18=sharebrained LibName18=asahi_kasei
LibName19=fiducial LibName19=ti
LibName20=diode
[pcbnew]
version=1
PageLayoutDescrFile=
LastNetListRead=portapack_h1.net
PadDrill=0
PadDrillOvalY=0
PadSizeH=2.25
PadSizeV=2.25
PcbTextSizeV=1.5
PcbTextSizeH=1.5
PcbTextThickness=0.3
ModuleTextSizeV=0.6095999999999999
ModuleTextSizeH=0.6095999999999999
ModuleTextSizeThickness=0.12
SolderMaskClearance=0.07619999999999999
SolderMaskMinWidth=0.1016
DrawSegmentWidth=0.1524
BoardOutlineThickness=0.09999999999999999
ModuleOutlineThickness=0.1524
[schematic_editor]
version=1
PageLayoutDescrFile=
PlotDirectoryName=
SubpartIdSeparator=0
SubpartFirstId=65
NetFmtName=Pcbnew
SpiceForceRefPrefix=0
SpiceUseNetNumbers=0
LabSize=60

View File

@ -1,14 +1,10 @@
EESchema Schematic File Version 2 EESchema Schematic File Version 2
LIBS:portapack_h1-rescue
LIBS:hackrf_expansion LIBS:hackrf_expansion
LIBS:wolfson
LIBS:passive LIBS:passive
LIBS:lcd_kingtech
LIBS:supply LIBS:supply
LIBS:io_expander
LIBS:trs_jack LIBS:trs_jack
LIBS:battery LIBS:battery
LIBS:mosfet
LIBS:microphone
LIBS:sd LIBS:sd
LIBS:ck LIBS:ck
LIBS:altera LIBS:altera
@ -18,257 +14,239 @@ LIBS:header
LIBS:hole LIBS:hole
LIBS:sharebrained LIBS:sharebrained
LIBS:fiducial LIBS:fiducial
LIBS:eastrising
LIBS:on_semi
LIBS:asahi_kasei
LIBS:ti
LIBS:diode
LIBS:portapack_h1-cache LIBS:portapack_h1-cache
EELAYER 25 0 EELAYER 25 0
EELAYER END EELAYER END
$Descr A4 11693 8268 $Descr A4 11693 8268
encoding utf-8 encoding utf-8
Sheet 1 4 Sheet 1 5
Title "PortaPack H1" Title "PortaPack H1"
Date "21 Aug 2015" Date "2017-05-22"
Rev "20150821" Rev "20170522"
Comp "ShareBrained Technology, Inc." Comp "ShareBrained Technology, Inc."
Comment1 "Copyright © 2014, 2015 Jared Boone" Comment1 "Copyright © 2014-2017 Jared Boone"
Comment2 "License: GNU General Public License, version 2" Comment2 "License: GNU General Public License, version 2"
Comment3 "" Comment3 ""
Comment4 "" Comment4 ""
$EndDescr $EndDescr
$Comp $Comp
L HOLE1 H1
U 1 1 5369BBC4
P 9500 2000
F 0 "H1" H 9500 2150 60 0000 C CNN
F 1 "HOLE1" H 9500 1850 60 0000 C CNN
F 2 "hole:HOLE_3200UM_VIAS" H 9500 2000 60 0001 C CNN
F 3 "" H 9500 2000 60 0000 C CNN
1 9500 2000
1 0 0 -1
$EndComp
$Comp
L HOLE1 H2 L HOLE1 H2
U 1 1 5369BBD8 U 1 1 5369BBD8
P 9500 2500 P 9500 1900
F 0 "H2" H 9500 2650 60 0000 C CNN F 0 "H2" H 9500 2050 60 0000 C CNN
F 1 "HOLE1" H 9500 2350 60 0000 C CNN F 1 "HOLE1" H 9500 1750 60 0000 C CNN
F 2 "hole:HOLE_3200UM_VIAS" H 9500 2500 60 0001 C CNN F 2 "hole:HOLE_3200UM_VIAS" H 9500 1900 60 0001 C CNN
F 3 "" H 9500 2500 60 0000 C CNN F 3 "" H 9500 1900 60 0000 C CNN
1 9500 2500 1 9500 1900
1 0 0 -1 1 0 0 -1
$EndComp $EndComp
$Comp $Comp
L HOLE1 H3 L HOLE1 H3
U 1 1 5369BBEC U 1 1 5369BBEC
P 9500 3000 P 9500 2400
F 0 "H3" H 9500 3150 60 0000 C CNN F 0 "H3" H 9500 2550 60 0000 C CNN
F 1 "HOLE1" H 9500 2850 60 0000 C CNN F 1 "HOLE1" H 9500 2250 60 0000 C CNN
F 2 "hole:HOLE_3200UM_VIAS" H 9500 3000 60 0001 C CNN F 2 "hole:HOLE_3200UM_VIAS" H 9500 2400 60 0001 C CNN
F 3 "" H 9500 3000 60 0000 C CNN F 3 "" H 9500 2400 60 0000 C CNN
1 9500 3000 1 9500 2400
1 0 0 -1 1 0 0 -1
$EndComp $EndComp
$Comp $Comp
L HOLE1 H4 L HOLE1 H4
U 1 1 5369BC00 U 1 1 5369BC00
P 9500 3500 P 9500 2900
F 0 "H4" H 9500 3650 60 0000 C CNN F 0 "H4" H 9500 3050 60 0000 C CNN
F 1 "HOLE1" H 9500 3350 60 0000 C CNN F 1 "HOLE1" H 9500 2750 60 0000 C CNN
F 2 "hole:HOLE_3200UM_VIAS" H 9500 3500 60 0001 C CNN F 2 "hole:HOLE_3200UM_VIAS" H 9500 2900 60 0001 C CNN
F 3 "" H 9500 3500 60 0000 C CNN F 3 "" H 9500 2900 60 0000 C CNN
1 9500 3500 1 9500 2900
1 0 0 -1 1 0 0 -1
$EndComp $EndComp
$Comp $Comp
L HOLE1 H5 L HOLE1 H5
U 1 1 5369BC14 U 1 1 5369BC14
P 9500 4000 P 9500 3400
F 0 "H5" H 9500 4150 60 0000 C CNN F 0 "H5" H 9500 3550 60 0000 C CNN
F 1 "HOLE1" H 9500 3850 60 0000 C CNN F 1 "HOLE1" H 9500 3250 60 0000 C CNN
F 2 "hole:HOLE_3200UM_VIAS" H 9500 4000 60 0001 C CNN F 2 "hole:HOLE_3200UM_VIAS" H 9500 3400 60 0001 C CNN
F 3 "" H 9500 4000 60 0000 C CNN F 3 "" H 9500 3400 60 0000 C CNN
1 9500 4000 1 9500 3400
1 0 0 -1 1 0 0 -1
$EndComp $EndComp
$Sheet $Sheet
S 2800 1900 900 3300 S 2800 1600 900 4700
U 53A8BFC3 U 53A8BFC3
F0 "audio" 50 F0 "audio" 50
F1 "audio.sch" 50 F1 "audio.sch" 50
F2 "I2S0_SCK" I R 3700 2300 60 F2 "SCL" I R 3700 2500 60
F3 "I2S0_TX_SDA" I R 3700 2500 60 F3 "SDA" B R 3700 2600 60
F4 "I2S0_MCLK" I R 3700 2200 60 F4 "PDN#" I R 3700 1700 60
F5 "I2S0_WS" I R 3700 2400 60 F5 "BICK" B R 3700 2000 60
F6 "SCL" I R 3700 2800 60 F6 "LRCK" B R 3700 2100 60
F7 "SDA" B R 3700 2900 60 F7 "SDTO" O R 3700 2300 60
F8 "I2S0_RX_SDA" O R 3700 2600 60 F8 "MCKI" I R 3700 1900 60
F9 "SDTI" I R 3700 2200 60
F10 "SVDD" I R 3700 6200 60
F11 "AVDD" I R 3700 6100 60
F12 "DVDD" I R 3700 6000 60
F13 "TVDD" I R 3700 5900 60
$EndSheet $EndSheet
Wire Wire Line Wire Wire Line
9800 2500 9700 2500 9800 1900 9700 1900
Wire Wire Line Wire Wire Line
9800 3000 9700 3000 9800 2400 9700 2400
Wire Wire Line Wire Wire Line
9800 3500 9700 3500 9800 2900 9700 2900
$Sheet $Sheet
S 7600 1900 900 3300 S 7600 1600 900 4700
U 53A9129D U 53A9129D
F0 "lcd_sw_sd" 50 F0 "lcd_sw_sd" 50
F1 "lcd_sw_sd.sch" 50 F1 "lcd_sw_sd.sch" 50
F2 "LCD_RS" I L 7600 2400 60 F2 "LCD_RS" I L 7600 2100 60
F3 "LCD_RD#" I L 7600 2500 60 F3 "LCD_RD#" I L 7600 2200 60
F4 "LCD_WR#" I L 7600 2600 60 F4 "LCD_WR#" I L 7600 2300 60
F5 "LCD_RESET#" I L 7600 2100 60 F5 "LCD_RESET#" I L 7600 1700 60
F6 "LCD_TE" O L 7600 3000 60 F6 "LCD_TE" O L 7600 2700 60
F7 "SW_SEL" O L 7600 4300 60 F7 "SW_SEL" O L 7600 4000 60
F8 "SW_ROT_A" O L 7600 4100 60 F8 "SW_ROT_A" O L 7600 3800 60
F9 "SW_ROT_B" O L 7600 4200 60 F9 "SW_ROT_B" O L 7600 3900 60
F10 "SW_D" O L 7600 3900 60 F10 "SW_D" O L 7600 3600 60
F11 "SW_R" O L 7600 3800 60 F11 "SW_R" O L 7600 3500 60
F12 "SW_U" O L 7600 3700 60 F12 "SW_U" O L 7600 3400 60
F13 "SW_L" O L 7600 4000 60 F13 "SW_L" O L 7600 3700 60
F14 "SD_DAT2" B L 7600 5000 60 F14 "SD_DAT2" B L 7600 4700 60
F15 "SD_DAT3" B L 7600 5100 60 F15 "SD_DAT3" B L 7600 4800 60
F16 "SD_CMD" B L 7600 4700 60 F16 "SD_CMD" B L 7600 4400 60
F17 "SD_CLK" I L 7600 4600 60 F17 "SD_CLK" I L 7600 4300 60
F18 "SD_DAT0" B L 7600 4800 60 F18 "SD_DAT0" B L 7600 4500 60
F19 "SD_DAT1" B L 7600 4900 60 F19 "SD_DAT1" B L 7600 4600 60
F20 "SD_CD" O L 7600 4500 60 F20 "SD_CD" O L 7600 4200 60
F21 "TP_R" B L 7600 3300 60 F21 "TP_R" B L 7600 3000 60
F22 "TP_D" B L 7600 3400 60 F22 "TP_D" B L 7600 3100 60
F23 "TP_L" B L 7600 3500 60 F23 "TP_L" B L 7600 3200 60
F24 "TP_U" B L 7600 3200 60 F24 "TP_U" B L 7600 2900 60
F25 "LCD_DB[15..0]" B L 7600 2700 60 F25 "LCD_DB[15..0]" B L 7600 2400 60
F26 "LCD_BACKLIGHT" I L 7600 2000 60 F26 "LCD_BACKLIGHT" I L 7600 1900 60
F27 "LCD_CS#" I L 7600 2000 60
F28 "LCD_VBL" I L 7600 6200 60
$EndSheet $EndSheet
Wire Bus Line Wire Bus Line
6600 2700 7600 2700 6600 2400 7600 2400
$Sheet $Sheet
S 4700 1900 1900 3300 S 4700 1600 1900 3700
U 53A8C780 U 53A8C780
F0 "hackrf_if" 50 F0 "hackrf_if" 50
F1 "hackrf_if.sch" 50 F1 "hackrf_if.sch" 50
F2 "LCD_TE" I R 6600 3000 60 F2 "LCD_TE" I R 6600 2700 60
F3 "SW_R" I R 6600 3800 60 F3 "SW_R" I R 6600 3500 60
F4 "SW_ROT_B" I R 6600 4200 60 F4 "SW_ROT_B" I R 6600 3900 60
F5 "SW_ROT_A" I R 6600 4100 60 F5 "SW_ROT_A" I R 6600 3800 60
F6 "SW_D" I R 6600 3900 60 F6 "SW_D" I R 6600 3600 60
F7 "SW_SEL" I R 6600 4300 60 F7 "SW_SEL" I R 6600 4000 60
F8 "SW_U" I R 6600 3700 60 F8 "SW_U" I R 6600 3400 60
F9 "SW_L" I R 6600 4000 60 F9 "SW_L" I R 6600 3700 60
F10 "LCD_RESET#" O R 6600 2100 60 F10 "LCD_RESET#" O R 6600 1700 60
F11 "LCD_RS" O R 6600 2400 60 F11 "LCD_RS" O R 6600 2100 60
F12 "LCD_RD#" O R 6600 2500 60 F12 "LCD_RD#" O R 6600 2200 60
F13 "LCD_WR#" O R 6600 2600 60 F13 "LCD_WR#" O R 6600 2300 60
F14 "TP_U" B R 6600 3200 60 F14 "TP_U" B R 6600 2900 60
F15 "TP_L" B R 6600 3500 60 F15 "TP_L" B R 6600 3200 60
F16 "TP_D" B R 6600 3400 60 F16 "TP_D" B R 6600 3100 60
F17 "TP_R" B R 6600 3300 60 F17 "TP_R" B R 6600 3000 60
F18 "I2S0_TX_SDA" O L 4700 2500 60 F18 "I2S0_TX_SDA" O L 4700 2200 60
F19 "I2S0_WS" O L 4700 2400 60 F19 "I2S0_MCLK" O L 4700 1900 60
F20 "I2S0_MCLK" O L 4700 2200 60 F20 "SDA" B L 4700 2600 60
F21 "I2S0_SCK" O L 4700 2300 60 F21 "SCL" O L 4700 2500 60
F22 "SDA" B L 4700 2900 60 F22 "SD_CD" I R 6600 4200 60
F23 "SCL" O L 4700 2800 60 F23 "SD_DAT2" B R 6600 4700 60
F24 "SD_CD" I R 6600 4500 60 F24 "SD_DAT0" B R 6600 4500 60
F25 "SD_DAT2" B R 6600 5000 60 F25 "SD_CMD" B R 6600 4400 60
F26 "SD_DAT0" B R 6600 4800 60 F26 "SD_CLK" O R 6600 4300 60
F27 "SD_CMD" B R 6600 4700 60 F27 "SD_DAT3" B R 6600 4800 60
F28 "SD_CLK" O R 6600 4600 60 F28 "SD_DAT1" B R 6600 4600 60
F29 "SD_DAT3" B R 6600 5100 60 F29 "I2S0_RX_SDA" I L 4700 2300 60
F30 "SD_DAT1" B R 6600 4900 60 F30 "LCD_DB[15..0]" B R 6600 2400 60
F31 "I2S0_RX_SDA" I L 4700 2600 60 F31 "LCD_BACKLIGHT" O R 6600 1900 60
F32 "LCD_DB[15..0]" B R 6600 2700 60 F32 "LCD_CS#" O R 6600 2000 60
F33 "LCD_BACKLIGHT" O R 6600 2000 60 F33 "AUDIO_RESET#" O L 4700 1700 60
F34 "I2S0_WS" B L 4700 2100 60
F35 "I2S0_SCK" B L 4700 2000 60
F36 "VIN" I R 6600 5200 60
F37 "VBUS" O R 6600 5000 60
F38 "VBUSCTRL" I R 6600 5100 60
F39 "VBAT" I L 4700 5200 60
$EndSheet $EndSheet
Wire Wire Line Wire Wire Line
6600 2000 7600 2000 6600 1900 7600 1900
Wire Wire Line
7600 1700 6600 1700
Wire Wire Line Wire Wire Line
7600 2100 6600 2100 7600 2100 6600 2100
Wire Wire Line Wire Wire Line
7600 2400 6600 2400 6600 2200 7600 2200
Wire Wire Line Wire Wire Line
6600 2500 7600 2500 7600 2300 6600 2300
Wire Wire Line Wire Wire Line
7600 2600 6600 2600 6600 2700 7600 2700
Wire Wire Line
7600 2900 6600 2900
Wire Wire Line Wire Wire Line
6600 3000 7600 3000 6600 3000 7600 3000
Wire Wire Line Wire Wire Line
7600 3200 6600 3200 7600 3100 6600 3100
Wire Wire Line Wire Wire Line
6600 3300 7600 3300 6600 3200 7600 3200
Wire Wire Line Wire Wire Line
7600 3400 6600 3400 6600 3400 7600 3400
Wire Wire Line Wire Wire Line
6600 3500 7600 3500 7600 3500 6600 3500
Wire Wire Line Wire Wire Line
6600 3700 7600 3700 6600 3600 7600 3600
Wire Wire Line Wire Wire Line
7600 3800 6600 3800 7600 3700 6600 3700
Wire Wire Line Wire Wire Line
6600 3900 7600 3900 6600 3800 7600 3800
Wire Wire Line Wire Wire Line
7600 4000 6600 4000 7600 3900 6600 3900
Wire Wire Line Wire Wire Line
6600 4100 7600 4100 6600 4000 7600 4000
Wire Wire Line Wire Wire Line
7600 4200 6600 4200 6600 4200 7600 4200
Wire Wire Line Wire Wire Line
6600 4300 7600 4300 6600 4300 7600 4300
Wire Wire Line
7600 4400 6600 4400
Wire Wire Line Wire Wire Line
6600 4500 7600 4500 6600 4500 7600 4500
Wire Wire Line Wire Wire Line
6600 4600 7600 4600 7600 4600 6600 4600
Wire Wire Line Wire Wire Line
7600 4700 6600 4700 6600 4700 7600 4700
Wire Wire Line Wire Wire Line
6600 4800 7600 4800 7600 4800 6600 4800
Wire Wire Line Wire Wire Line
7600 4900 6600 4900 3700 1900 4700 1900
Wire Wire Line Wire Wire Line
6600 5000 7600 5000 4700 2000 3700 2000
Wire Wire Line Wire Wire Line
7600 5100 6600 5100 3700 2100 4700 2100
Wire Wire Line Wire Wire Line
3700 2200 4700 2200 4700 2200 3700 2200
Wire Wire Line Wire Wire Line
4700 2300 3700 2300 3700 2300 4700 2300
Wire Wire Line
3700 2400 4700 2400
Wire Wire Line Wire Wire Line
4700 2500 3700 2500 4700 2500 3700 2500
Wire Wire Line Wire Wire Line
3700 2600 4700 2600 3700 2600 4700 2600
Wire Wire Line Wire Wire Line
4700 2800 3700 2800 9800 1900 9800 3500
Wire Wire Line Connection ~ 9800 2400
3700 2900 4700 2900 Connection ~ 9800 2900
Wire Wire Line
9700 2000 9800 2000
Wire Wire Line
9800 2000 9800 4100
Connection ~ 9800 2500
Connection ~ 9800 3000
Connection ~ 9800 3500
$Comp
L SHAREBRAINED LOGO1
U 1 1 53B1AE0D
P 6050 7000
F 0 "LOGO1" H 6050 7050 60 0000 C CNN
F 1 "SHAREBRAINED" H 6050 6950 60 0000 C CNN
F 2 "sharebrained:sharebrained_text_300" H 6050 7000 60 0001 C CNN
F 3 "" H 6050 7000 60 0000 C CNN
1 6050 7000
1 0 0 -1
$EndComp
$Comp
L PORTAPACK_H1 LOGO2
U 1 1 53B1B509
P 6050 7450
F 0 "LOGO2" H 6050 7500 60 0000 C CNN
F 1 "PORTAPACK_H1" H 6050 7400 60 0000 C CNN
F 2 "sharebrained:portapack_text_300" H 6050 7450 60 0001 C CNN
F 3 "" H 6050 7450 60 0000 C CNN
1 6050 7450
1 0 0 -1
$EndComp
$Comp $Comp
L FIDUCIAL FID1 L FIDUCIAL FID1
U 1 1 53B309AC U 1 1 53B309AC
@ -316,15 +294,68 @@ $EndComp
$Comp $Comp
L GND #PWR01 L GND #PWR01
U 1 1 53B3303D U 1 1 53B3303D
P 9800 4100 P 9800 3500
F 0 "#PWR01" H 9800 4100 30 0001 C CNN F 0 "#PWR01" H 9800 3500 30 0001 C CNN
F 1 "GND" H 9800 4030 30 0001 C CNN F 1 "GND" H 9800 3430 30 0001 C CNN
F 2 "" H 9800 4100 60 0000 C CNN F 2 "" H 9800 3500 60 0000 C CNN
F 3 "" H 9800 4100 60 0000 C CNN F 3 "" H 9800 3500 60 0000 C CNN
1 9800 4100 1 9800 3500
1 0 0 -1 1 0 0 -1
$EndComp $EndComp
Wire Wire Line Wire Wire Line
9700 4000 9800 4000 9700 3400 9800 3400
Connection ~ 9800 4000 Connection ~ 9800 3400
Wire Wire Line
6600 2000 7600 2000
Wire Wire Line
4700 1700 3700 1700
$Sheet
S 4700 5600 1900 700
U 58CFF3E3
F0 "power" 50
F1 "power.sch" 50
F2 "LCD_VBL" O R 6600 6200 60
F3 "AUDIO_SVDD" O L 4700 6200 60
F4 "AUDIO_AVDD" O L 4700 6100 60
F5 "AUDIO_DVDD" O L 4700 6000 60
F6 "AUDIO_TVDD" O L 4700 5900 60
F7 "VBUS" I R 6600 5700 60
F8 "VBUSCTRL" O R 6600 5800 60
F9 "VIN" O R 6600 5900 60
F10 "VBAT" O L 4700 5700 60
$EndSheet
Wire Wire Line
6600 6200 7600 6200
Wire Wire Line
3700 6200 4700 6200
Wire Wire Line
4700 6100 3700 6100
Wire Wire Line
3700 6000 4700 6000
Wire Wire Line
4700 5900 3700 5900
Wire Wire Line
4700 5700 4500 5700
Wire Wire Line
4500 5700 4500 5200
Wire Wire Line
4500 5200 4700 5200
Wire Wire Line
6600 5700 6800 5700
Wire Wire Line
6800 5700 6800 5000
Wire Wire Line
6800 5000 6600 5000
Wire Wire Line
6600 5100 6900 5100
Wire Wire Line
6900 5100 6900 5800
Wire Wire Line
6900 5800 6600 5800
Wire Wire Line
6600 5200 7000 5200
Wire Wire Line
7000 5200 7000 5900
Wire Wire Line
7000 5900 6600 5900
$EndSCHEMATC $EndSCHEMATC

View File

@ -0,0 +1,794 @@
EESchema Schematic File Version 2
LIBS:portapack_h1-rescue
LIBS:hackrf_expansion
LIBS:passive
LIBS:supply
LIBS:trs_jack
LIBS:battery
LIBS:sd
LIBS:ck
LIBS:altera
LIBS:regulator
LIBS:tp
LIBS:header
LIBS:hole
LIBS:sharebrained
LIBS:fiducial
LIBS:eastrising
LIBS:on_semi
LIBS:asahi_kasei
LIBS:ti
LIBS:diode
LIBS:portapack_h1-cache
EELAYER 25 0
EELAYER END
$Descr A4 11693 8268
encoding utf-8
Sheet 5 5
Title "PortaPack H1"
Date "2017-05-22"
Rev "20170522"
Comp "ShareBrained Technology, Inc."
Comment1 "Copyright © 2014-2017 Jared Boone"
Comment2 "License: GNU General Public License, version 2"
Comment3 ""
Comment4 ""
$EndDescr
Text HLabel 10450 4550 0 60 Output ~ 0
LCD_VBL
$Comp
L +3.3V #PWR077
U 1 1 58CFF694
P 10550 4450
F 0 "#PWR077" H 10550 4410 30 0001 C CNN
F 1 "+3.3V" H 10550 4560 30 0000 C CNN
F 2 "" H 10550 4450 60 0000 C CNN
F 3 "" H 10550 4450 60 0000 C CNN
1 10550 4450
1 0 0 -1
$EndComp
Text HLabel 6300 2200 2 60 Output ~ 0
AUDIO_SVDD
Text HLabel 10450 4750 0 60 Output ~ 0
AUDIO_AVDD
Text HLabel 10450 5200 0 60 Output ~ 0
AUDIO_DVDD
Text HLabel 10450 4850 0 60 Output ~ 0
AUDIO_TVDD
$Comp
L +1.8V #PWR078
U 1 1 58CFF6A8
P 10550 5100
F 0 "#PWR078" H 10550 5240 20 0001 C CNN
F 1 "+1.8V" H 10550 5210 30 0000 C CNN
F 2 "" H 10550 5100 60 0000 C CNN
F 3 "" H 10550 5100 60 0000 C CNN
1 10550 5100
1 0 0 -1
$EndComp
$Comp
L REGULATOR_SOT23_5 U2
U 1 1 58CFF91A
P 8400 2900
F 0 "U2" H 8400 3150 50 0000 C CNN
F 1 "TCR2EF18,LM(CT" H 8000 2650 50 0000 C CNN
F 2 "ipc_sot:IPC_SOT23-5P95_275X135L40X40N" H 8400 2900 60 0001 C CNN
F 3 "http://toshiba.semicon-storage.com/ap-en/product/linear/power-supply/detail.TCR2EF18.html" H 8400 2900 60 0001 C CNN
F 4 "Toshiba" H 8400 2900 60 0001 C CNN "Mfr"
F 5 "TCR2EF18,LM(CT" H 8400 2900 60 0001 C CNN "Part"
1 8400 2900
1 0 0 -1
$EndComp
$Comp
L C C38
U 1 1 58CFF923
P 7500 3100
F 0 "C38" H 7550 3200 50 0000 L CNN
F 1 "10U" H 7550 3000 50 0000 L CNN
F 2 "ipc_capc:IPC_CAPC2012X135L45N" H 7500 3100 60 0001 C CNN
F 3 "" H 7500 3100 60 0000 C CNN
F 4 "Murata" H 7500 3100 60 0001 C CNN "Mfr"
F 5 "GRM21BR61A106KE19" H 7500 3100 60 0001 C CNN "Part"
1 7500 3100
-1 0 0 -1
$EndComp
$Comp
L C C40
U 1 1 58CFF92C
P 9300 3100
F 0 "C40" H 9350 3200 50 0000 L CNN
F 1 "10U" H 9350 3000 50 0000 L CNN
F 2 "ipc_capc:IPC_CAPC2012X135L45N" H 9300 3100 60 0001 C CNN
F 3 "" H 9300 3100 60 0000 C CNN
F 4 "Murata" H 9300 3100 60 0001 C CNN "Mfr"
F 5 "GRM21BR61A106KE19" H 9300 3100 60 0001 C CNN "Part"
1 9300 3100
-1 0 0 -1
$EndComp
$Comp
L GND #PWR079
U 1 1 58CFF933
P 8400 3300
F 0 "#PWR079" H 8400 3300 30 0001 C CNN
F 1 "GND" H 8400 3230 30 0001 C CNN
F 2 "" H 8400 3300 60 0000 C CNN
F 3 "" H 8400 3300 60 0000 C CNN
1 8400 3300
1 0 0 -1
$EndComp
$Comp
L GND #PWR080
U 1 1 58CFF939
P 7500 3400
F 0 "#PWR080" H 7500 3400 30 0001 C CNN
F 1 "GND" H 7500 3330 30 0001 C CNN
F 2 "" H 7500 3400 60 0000 C CNN
F 3 "" H 7500 3400 60 0000 C CNN
1 7500 3400
1 0 0 -1
$EndComp
$Comp
L GND #PWR081
U 1 1 58CFF93F
P 9300 3400
F 0 "#PWR081" H 9300 3400 30 0001 C CNN
F 1 "GND" H 9300 3330 30 0001 C CNN
F 2 "" H 9300 3400 60 0000 C CNN
F 3 "" H 9300 3400 60 0000 C CNN
1 9300 3400
1 0 0 -1
$EndComp
$Comp
L C C39
U 1 1 58CFF945
P 8900 3300
F 0 "C39" H 8950 3400 50 0000 L CNN
F 1 "R" H 8950 3200 50 0001 L CNN
F 2 "ipc_capc:IPC_CAPC1608X90L35N" H 9100 3300 60 0001 C CNN
F 3 "" H 8900 3300 60 0000 C CNN
F 4 "DNP" H 9000 3200 50 0000 C CNN "DNP"
1 8900 3300
-1 0 0 -1
$EndComp
$Comp
L GND #PWR082
U 1 1 58CFF94C
P 8900 3600
F 0 "#PWR082" H 8900 3600 30 0001 C CNN
F 1 "GND" H 8900 3530 30 0001 C CNN
F 2 "" H 8900 3600 60 0000 C CNN
F 3 "" H 8900 3600 60 0000 C CNN
1 8900 3600
1 0 0 -1
$EndComp
$Comp
L +1.8V #PWR083
U 1 1 58CFF952
P 9300 2700
F 0 "#PWR083" H 9300 2840 20 0001 C CNN
F 1 "+1.8V" H 9300 2810 30 0000 C CNN
F 2 "" H 9300 2700 60 0000 C CNN
F 3 "" H 9300 2700 60 0000 C CNN
1 9300 2700
1 0 0 -1
$EndComp
$Comp
L +3.3V #PWR084
U 1 1 58CFF958
P 7500 2700
F 0 "#PWR084" H 7500 2660 30 0001 C CNN
F 1 "+3.3V" H 7500 2810 30 0000 C CNN
F 2 "" H 7500 2700 60 0000 C CNN
F 3 "" H 7500 2700 60 0000 C CNN
1 7500 2700
1 0 0 -1
$EndComp
Text HLabel 2800 2500 0 60 Input ~ 0
VBUS
Text HLabel 2800 3200 0 60 Output ~ 0
VBUSCTRL
Text HLabel 6300 2400 2 60 Output ~ 0
VIN
$Comp
L BATTERY BT1
U 1 1 58D008D0
P 9700 1350
F 0 "BT1" V 9600 1200 50 0000 C CNN
F 1 "BATTERY" V 9800 1150 50 0001 C CNN
F 2 "bat_coin:MPD_BU2032SM-BT-G" H 9700 1350 60 0001 C CNN
F 3 "http://www.memoryprotectiondevices.com/datasheets/BU2032SM-BT-GTR-datasheet.pdf" H 9700 1350 60 0001 C CNN
F 4 "MPD" H 9700 1350 60 0001 C CNN "Mfr"
F 5 "BU2032SM-BT-GTR" H 9700 1350 60 0001 C CNN "Part"
1 9700 1350
0 1 1 0
$EndComp
$Comp
L GND #PWR085
U 1 1 58D008D7
P 9700 1650
F 0 "#PWR085" H 9700 1650 30 0001 C CNN
F 1 "GND" H 9700 1580 30 0001 C CNN
F 2 "" H 9700 1650 60 0000 C CNN
F 3 "" H 9700 1650 60 0000 C CNN
1 9700 1650
1 0 0 -1
$EndComp
$Comp
L C C41
U 1 1 58D008E2
P 10200 1350
F 0 "C41" H 10250 1450 50 0000 L CNN
F 1 "10U" H 10250 1250 50 0001 L CNN
F 2 "ipc_capc:IPC_CAPC2012X135L45N" H 10200 1350 60 0001 C CNN
F 3 "" H 10200 1350 60 0000 C CNN
F 4 "Murata" H 10200 1350 60 0001 C CNN "Mfr"
F 5 "GRM21BR61A106KE19" H 10200 1350 60 0001 C CNN "Part"
F 6 "DNP" H 10300 1250 50 0000 C CNN "DNP"
1 10200 1350
-1 0 0 -1
$EndComp
$Comp
L GND #PWR086
U 1 1 58D008E9
P 10200 1650
F 0 "#PWR086" H 10200 1650 30 0001 C CNN
F 1 "GND" H 10200 1580 30 0001 C CNN
F 2 "" H 10200 1650 60 0000 C CNN
F 3 "" H 10200 1650 60 0000 C CNN
1 10200 1650
1 0 0 -1
$EndComp
Text HLabel 10300 1050 2 60 Output ~ 0
VBAT
$Comp
L BQ24075 U6
U 1 1 58F1AA75
P 4500 3100
F 0 "U6" H 4500 3150 60 0000 C CNN
F 1 "BQ24075RGT" H 4500 3050 60 0001 C CNN
F 2 "ipc_qfn:IPC_QFN17P50_300X300X100L40X25T160N" H 4600 3350 60 0001 C CNN
F 3 "http://www.ti.com/lit/ds/symlink/bq24075.pdf" H 4600 3350 60 0001 C CNN
F 4 "Texas Instruments" H 4500 3100 60 0001 C CNN "Mfr"
F 5 "BQ24075RGT" H 4500 3100 60 0001 C CNN "Part"
F 6 "DNP" H 4500 3050 50 0000 C CNN "DNP"
1 4500 3100
1 0 0 -1
$EndComp
$Comp
L C C1
U 1 1 58F1AC44
P 3400 2800
F 0 "C1" H 3450 2900 50 0000 L CNN
F 1 "1U" H 3450 2700 50 0001 L CNN
F 2 "ipc_capc:IPC_CAPC2012X135L45N" H 3400 2800 60 0001 C CNN
F 3 "" H 3400 2800 60 0000 C CNN
F 4 "Murata" H 3400 2800 60 0001 C CNN "Mfr"
F 5 "DNP" H 3500 2700 50 0000 C CNN "DNP"
F 6 ">26V" H 3250 2700 50 0000 C CNN "WVDC"
1 3400 2800
-1 0 0 -1
$EndComp
$Comp
L GND #PWR087
U 1 1 58F1AC96
P 3700 3000
F 0 "#PWR087" H 3700 3000 30 0001 C CNN
F 1 "GND" H 3700 2930 30 0001 C CNN
F 2 "" H 3700 3000 60 0000 C CNN
F 3 "" H 3700 3000 60 0000 C CNN
1 3700 3000
0 1 1 0
$EndComp
$Comp
L GND #PWR088
U 1 1 58F1ACB9
P 3700 3100
F 0 "#PWR088" H 3700 3100 30 0001 C CNN
F 1 "GND" H 3700 3030 30 0001 C CNN
F 2 "" H 3700 3100 60 0000 C CNN
F 3 "" H 3700 3100 60 0000 C CNN
1 3700 3100
0 1 1 0
$EndComp
$Comp
L GND #PWR089
U 1 1 58F1AD43
P 3400 3100
F 0 "#PWR089" H 3400 3100 30 0001 C CNN
F 1 "GND" H 3400 3030 30 0001 C CNN
F 2 "" H 3400 3100 60 0000 C CNN
F 3 "" H 3400 3100 60 0000 C CNN
1 3400 3100
1 0 0 -1
$EndComp
$Comp
L C C16
U 1 1 58F1AE50
P 5600 2700
F 0 "C16" H 5650 2800 50 0000 L CNN
F 1 "4U7" H 5650 2600 50 0001 L CNN
F 2 "ipc_capc:IPC_CAPC2012X135L45N" H 5600 2700 60 0001 C CNN
F 3 "" H 5600 2700 60 0000 C CNN
F 4 "Murata" H 5600 2700 60 0001 C CNN "Mfr"
F 5 "DNP" H 5700 2600 50 0000 C CNN "DNP"
1 5600 2700
-1 0 0 -1
$EndComp
$Comp
L GND #PWR090
U 1 1 58F1AEB9
P 5600 3000
F 0 "#PWR090" H 5600 3000 30 0001 C CNN
F 1 "GND" H 5600 2930 30 0001 C CNN
F 2 "" H 5600 3000 60 0000 C CNN
F 3 "" H 5600 3000 60 0000 C CNN
1 5600 3000
1 0 0 -1
$EndComp
$Comp
L C C15
U 1 1 58F1B1AB
P 3500 4000
F 0 "C15" H 3550 4100 50 0000 L CNN
F 1 "4U7" H 3550 3900 50 0001 L CNN
F 2 "ipc_capc:IPC_CAPC2012X135L45N" H 3500 4000 60 0001 C CNN
F 3 "" H 3500 4000 60 0000 C CNN
F 4 "Murata" H 3500 4000 60 0001 C CNN "Mfr"
F 5 "DNP" H 3600 3900 50 0000 C CNN "DNP"
1 3500 4000
-1 0 0 -1
$EndComp
$Comp
L GND #PWR091
U 1 1 58F1B4E6
P 3500 4300
F 0 "#PWR091" H 3500 4300 30 0001 C CNN
F 1 "GND" H 3500 4230 30 0001 C CNN
F 2 "" H 3500 4300 60 0000 C CNN
F 3 "" H 3500 4300 60 0000 C CNN
1 3500 4300
1 0 0 -1
$EndComp
Wire Wire Line
10450 4550 10550 4550
Wire Wire Line
10550 4450 10550 4850
Wire Wire Line
10550 4750 10450 4750
Connection ~ 10550 4550
Wire Wire Line
10550 4850 10450 4850
Connection ~ 10550 4750
Wire Wire Line
10450 5200 10550 5200
Wire Wire Line
10550 5200 10550 5100
Connection ~ 7900 2800
Wire Wire Line
7900 3000 7900 2800
Wire Wire Line
8000 3000 7900 3000
Connection ~ 7500 2800
Wire Wire Line
7500 2700 7500 2900
Wire Wire Line
7500 2800 8000 2800
Connection ~ 9300 2800
Wire Wire Line
8900 3500 8900 3600
Wire Wire Line
8900 3000 8900 3100
Wire Wire Line
8800 3000 8900 3000
Wire Wire Line
8400 3200 8400 3300
Wire Wire Line
9300 3300 9300 3400
Wire Wire Line
9300 2700 9300 2900
Wire Wire Line
8800 2800 9300 2800
Wire Wire Line
7500 3300 7500 3400
Wire Wire Line
9700 1550 9700 1650
Wire Wire Line
9700 1050 9700 1150
Wire Wire Line
10200 1150 10200 1050
Wire Wire Line
10200 1550 10200 1650
Wire Wire Line
9700 1050 10300 1050
Connection ~ 10200 1050
Wire Wire Line
2800 2500 3800 2500
Wire Wire Line
3800 3000 3700 3000
Wire Wire Line
3800 3100 3700 3100
Wire Wire Line
3400 3100 3400 3000
Wire Wire Line
3400 2600 3400 2500
Connection ~ 3400 2500
Wire Wire Line
5200 2400 6300 2400
Wire Wire Line
5300 2500 5200 2500
Wire Wire Line
5300 800 5300 2500
Connection ~ 5300 2400
Wire Wire Line
5600 2500 5600 2400
Connection ~ 5600 2400
Wire Wire Line
5600 2900 5600 3000
Wire Wire Line
2900 3700 3800 3700
Wire Wire Line
3500 3700 3500 3800
Wire Wire Line
3800 3600 3700 3600
Wire Wire Line
3700 3600 3700 3700
Connection ~ 3700 3700
Wire Wire Line
3500 4300 3500 4200
$Comp
L R R1
U 1 1 58F1CB6B
P 4200 4550
F 0 "R1" V 4280 4550 50 0000 C CNN
F 1 "R" V 4200 4550 50 0001 C CNN
F 2 "ipc_resc:IPC_RESC1005X40L25N" H 4200 4550 60 0001 C CNN
F 3 "" H 4200 4550 60 0000 C CNN
F 4 "Yageo" V 4200 4550 60 0001 C CNN "Mfr"
F 5 "DNP" V 4200 4550 50 0000 C CNN "DNP"
1 4200 4550
-1 0 0 -1
$EndComp
$Comp
L R R4
U 1 1 58F1CBFA
P 4500 4550
F 0 "R4" V 4580 4550 50 0000 C CNN
F 1 "1K91" V 4500 4550 50 0001 C CNN
F 2 "ipc_resc:IPC_RESC1005X40L25N" H 4500 4550 60 0001 C CNN
F 3 "" H 4500 4550 60 0000 C CNN
F 4 "Yageo" V 4500 4550 60 0001 C CNN "Mfr"
F 5 "DNP" V 4500 4550 50 0000 C CNN "DNP"
1 4500 4550
-1 0 0 -1
$EndComp
$Comp
L R R6
U 1 1 58F1CC38
P 4800 4550
F 0 "R6" V 4880 4550 50 0000 C CNN
F 1 "1K8" V 4800 4550 50 0001 C CNN
F 2 "ipc_resc:IPC_RESC1005X40L25N" H 4800 4550 60 0001 C CNN
F 3 "" H 4800 4550 60 0000 C CNN
F 4 "Yageo" V 4800 4550 60 0001 C CNN "Mfr"
F 5 "DNP" V 4800 4550 50 0000 C CNN "DNP"
1 4800 4550
-1 0 0 -1
$EndComp
$Comp
L GND #PWR092
U 1 1 58F1CC76
P 4800 4900
F 0 "#PWR092" H 4800 4900 30 0001 C CNN
F 1 "GND" H 4800 4830 30 0001 C CNN
F 2 "" H 4800 4900 60 0000 C CNN
F 3 "" H 4800 4900 60 0000 C CNN
1 4800 4900
1 0 0 -1
$EndComp
$Comp
L GND #PWR093
U 1 1 58F1CCA8
P 4500 4900
F 0 "#PWR093" H 4500 4900 30 0001 C CNN
F 1 "GND" H 4500 4830 30 0001 C CNN
F 2 "" H 4500 4900 60 0000 C CNN
F 3 "" H 4500 4900 60 0000 C CNN
1 4500 4900
1 0 0 -1
$EndComp
$Comp
L GND #PWR094
U 1 1 58F1CCDA
P 4200 4900
F 0 "#PWR094" H 4200 4900 30 0001 C CNN
F 1 "GND" H 4200 4830 30 0001 C CNN
F 2 "" H 4200 4900 60 0000 C CNN
F 3 "" H 4200 4900 60 0000 C CNN
1 4200 4900
1 0 0 -1
$EndComp
Wire Wire Line
4200 4300 4200 4200
Wire Wire Line
4500 4300 4500 4200
Wire Wire Line
4800 4300 4800 4200
Wire Wire Line
4800 4900 4800 4800
Wire Wire Line
4500 4900 4500 4800
Wire Wire Line
4200 4900 4200 4800
$Comp
L R R3
U 1 1 58F1D0EB
P 4300 1150
F 0 "R3" V 4380 1150 50 0000 C CNN
F 1 "1K5" V 4300 1150 50 0001 C CNN
F 2 "ipc_resc:IPC_RESC1005X40L25N" H 4300 1150 60 0001 C CNN
F 3 "" H 4300 1150 60 0000 C CNN
F 4 "Yageo" V 4300 1150 60 0001 C CNN "Mfr"
F 5 "DNP" V 4300 1150 50 0000 C CNN "DNP"
1 4300 1150
-1 0 0 -1
$EndComp
$Comp
L R R5
U 1 1 58F1D207
P 4700 1150
F 0 "R5" V 4780 1150 50 0000 C CNN
F 1 "1K5" V 4700 1150 50 0001 C CNN
F 2 "ipc_resc:IPC_RESC1005X40L25N" H 4700 1150 60 0001 C CNN
F 3 "" H 4700 1150 60 0000 C CNN
F 4 "Yageo" V 4700 1150 60 0001 C CNN "Mfr"
F 5 "DNP" V 4700 1150 50 0000 C CNN "DNP"
1 4700 1150
-1 0 0 -1
$EndComp
Wire Wire Line
4300 800 5300 800
Wire Wire Line
4700 800 4700 900
Wire Wire Line
4300 800 4300 900
Connection ~ 4700 800
Wire Wire Line
6300 2200 6100 2200
$Comp
L HEADER_1X2 J4
U 1 1 58F1DD77
P 2600 3750
F 0 "J4" H 2600 3950 60 0000 C CNN
F 1 "HEADER_1X2" H 2600 3550 60 0001 C CNN
F 2 "jst:JST_S2B-PH-SM4-TB" H 2600 3550 60 0001 C CNN
F 3 "http://www.jst-mfg.com/product/pdf/eng/ePH.pdf" H 2600 3550 60 0001 C CNN
F 4 "JST" H 2600 3750 60 0001 C CNN "Mfr"
F 5 "S2B-PH-SM4-TB" H 2600 3750 60 0001 C CNN "Part"
F 6 "DNP" H 2600 3750 50 0000 C CNN "DNP"
1 2600 3750
-1 0 0 -1
$EndComp
$Comp
L R R8
U 1 1 58F1E372
P 3450 3400
F 0 "R8" V 3530 3400 50 0000 C CNN
F 1 "10K" V 3450 3400 50 0001 C CNN
F 2 "ipc_resc:IPC_RESC1005X40L25N" H 3450 3400 60 0001 C CNN
F 3 "" H 3450 3400 60 0000 C CNN
F 4 "Yageo" V 3450 3400 60 0001 C CNN "Mfr"
F 5 "DNP" V 3450 3400 50 0000 C CNN "DNP"
1 3450 3400
0 1 -1 0
$EndComp
Connection ~ 3500 3700
$Comp
L GND #PWR095
U 1 1 58F1E667
P 3000 3900
F 0 "#PWR095" H 3000 3900 30 0001 C CNN
F 1 "GND" H 3000 3830 30 0001 C CNN
F 2 "" H 3000 3900 60 0000 C CNN
F 3 "" H 3000 3900 60 0000 C CNN
1 3000 3900
1 0 0 -1
$EndComp
Wire Wire Line
2900 3800 3000 3800
Wire Wire Line
3000 3800 3000 3900
Wire Wire Line
3800 3400 3700 3400
$Comp
L GND #PWR096
U 1 1 58F1EA88
P 3100 3400
F 0 "#PWR096" H 3100 3400 30 0001 C CNN
F 1 "GND" H 3100 3330 30 0001 C CNN
F 2 "" H 3100 3400 60 0000 C CNN
F 3 "" H 3100 3400 60 0000 C CNN
1 3100 3400
0 1 1 0
$EndComp
Wire Wire Line
3100 3400 3200 3400
Wire Wire Line
6100 2200 6100 2400
Connection ~ 6100 2400
$Comp
L R R7
U 1 1 58F1F0EF
P 3000 2850
F 0 "R7" V 3080 2850 50 0000 C CNN
F 1 "0R" V 3000 2850 50 0001 C CNN
F 2 "ipc_resc:IPC_RESC1005X40L25N" H 3000 2850 60 0001 C CNN
F 3 "" H 3000 2850 60 0000 C CNN
F 4 "Yageo" V 3000 2850 60 0001 C CNN "Mfr"
F 5 "DNP" V 3000 2850 50 0000 C CNN "DNP"
1 3000 2850
-1 0 0 -1
$EndComp
Wire Wire Line
2800 3200 3000 3200
Wire Wire Line
3000 3200 3000 3100
Wire Wire Line
3000 2600 3000 2500
Connection ~ 3000 2500
$Comp
L R R9
U 1 1 58F443CF
P 5300 4050
F 0 "R9" V 5380 4050 50 0000 C CNN
F 1 "10K" V 5300 4050 50 0001 C CNN
F 2 "ipc_resc:IPC_RESC1005X40L25N" H 5300 4050 60 0001 C CNN
F 3 "" H 5300 4050 60 0000 C CNN
F 4 "Yageo" V 5300 4050 60 0001 C CNN "Mfr"
F 5 "DNP" V 5300 4050 50 0000 C CNN "DNP"
1 5300 4050
-1 0 0 -1
$EndComp
$Comp
L GND #PWR097
U 1 1 58F4443F
P 5300 4400
F 0 "#PWR097" H 5300 4400 30 0001 C CNN
F 1 "GND" H 5300 4330 30 0001 C CNN
F 2 "" H 5300 4400 60 0000 C CNN
F 3 "" H 5300 4400 60 0000 C CNN
1 5300 4400
1 0 0 -1
$EndComp
Wire Wire Line
5300 4400 5300 4300
Wire Wire Line
5200 3700 5300 3700
Wire Wire Line
5300 3700 5300 3800
$Comp
L R R10
U 1 1 58F44562
P 5500 4050
F 0 "R10" V 5580 4050 50 0000 C CNN
F 1 "10K" V 5500 4050 50 0001 C CNN
F 2 "ipc_resc:IPC_RESC1005X40L25N" H 5500 4050 60 0001 C CNN
F 3 "" H 5500 4050 60 0000 C CNN
F 4 "Yageo" V 5500 4050 60 0001 C CNN "Mfr"
F 5 "DNP" V 5500 4050 50 0000 C CNN "DNP"
1 5500 4050
-1 0 0 -1
$EndComp
$Comp
L GND #PWR098
U 1 1 58F445B7
P 5500 4400
F 0 "#PWR098" H 5500 4400 30 0001 C CNN
F 1 "GND" H 5500 4330 30 0001 C CNN
F 2 "" H 5500 4400 60 0000 C CNN
F 3 "" H 5500 4400 60 0000 C CNN
1 5500 4400
1 0 0 -1
$EndComp
Wire Wire Line
5200 3600 5500 3600
Wire Wire Line
5500 3600 5500 3800
Wire Wire Line
5500 4300 5500 4400
$Comp
L R R14
U 1 1 58F44903
P 5900 3750
F 0 "R14" V 5980 3750 50 0000 C CNN
F 1 "10K" V 5900 3750 50 0001 C CNN
F 2 "ipc_resc:IPC_RESC1005X40L25N" H 5900 3750 60 0001 C CNN
F 3 "" H 5900 3750 60 0000 C CNN
F 4 "Yageo" V 5900 3750 60 0001 C CNN "Mfr"
F 5 "DNP" V 5900 3750 50 0000 C CNN "DNP"
1 5900 3750
-1 0 0 -1
$EndComp
$Comp
L R R13
U 1 1 58F4495E
P 5900 2950
F 0 "R13" V 5980 2950 50 0000 C CNN
F 1 "10K" V 5900 2950 50 0001 C CNN
F 2 "ipc_resc:IPC_RESC1005X40L25N" H 5900 2950 60 0001 C CNN
F 3 "" H 5900 2950 60 0000 C CNN
F 4 "Yageo" V 5900 2950 60 0001 C CNN "Mfr"
F 5 "DNP" V 5900 2950 50 0000 C CNN "DNP"
1 5900 2950
-1 0 0 -1
$EndComp
Wire Wire Line
5200 3300 5900 3300
Wire Wire Line
5900 3300 5900 3200
Wire Wire Line
5200 3400 5900 3400
Wire Wire Line
5900 3400 5900 3500
$Comp
L GND #PWR099
U 1 1 58F44AF6
P 5900 4100
F 0 "#PWR099" H 5900 4100 30 0001 C CNN
F 1 "GND" H 5900 4030 30 0001 C CNN
F 2 "" H 5900 4100 60 0000 C CNN
F 3 "" H 5900 4100 60 0000 C CNN
1 5900 4100
1 0 0 -1
$EndComp
Wire Wire Line
5900 4000 5900 4100
Wire Wire Line
5900 2700 5900 2400
Connection ~ 5900 2400
$Comp
L LED D1
U 1 1 58F5B932
P 4300 1700
AR Path="/58F5B932" Ref="D1" Part="1"
AR Path="/58CFF3E3/58F5B932" Ref="D1" Part="1"
F 0 "D1" H 4300 1800 50 0000 C CNN
F 1 "LED 0603 green" H 4300 1600 50 0001 C CNN
F 2 "ipc_ledc:IPC_LEDC1608X90L40N" H 4300 1700 60 0001 C CNN
F 3 "" H 4300 1700 60 0000 C CNN
F 4 "Kingbright" H 4300 1700 60 0001 C CNN "Mfr"
F 5 "APT1608SGC" H 4300 1700 60 0001 C CNN "Part"
F 6 "DNP" H 4300 1600 50 0000 C CNN "DNP"
1 4300 1700
0 -1 1 0
$EndComp
$Comp
L LED D2
U 1 1 58F5BA0B
P 4700 1700
AR Path="/58F5BA0B" Ref="D2" Part="1"
AR Path="/58CFF3E3/58F5BA0B" Ref="D2" Part="1"
F 0 "D2" H 4700 1800 50 0000 C CNN
F 1 "LED 0603 yellow" H 4700 1600 50 0001 C CNN
F 2 "ipc_ledc:IPC_LEDC1608X90L40N" H 4700 1700 60 0001 C CNN
F 3 "" H 4700 1700 60 0000 C CNN
F 4 "Kingbright" H 4700 1700 60 0001 C CNN "Mfr"
F 5 "APT1608SYCK" H 4700 1700 60 0001 C CNN "Part"
F 6 "DNP" H 4700 1600 50 0000 C CNN "DNP"
1 4700 1700
0 -1 1 0
$EndComp
Wire Wire Line
4300 1500 4300 1400
Wire Wire Line
4700 1500 4700 1400
Wire Wire Line
4700 2000 4700 1900
Wire Wire Line
4300 2000 4300 1900
Text Label 3100 3700 0 60 ~ 0
BBAT
Text Notes 1200 4700 0 60 ~ 0
TODO:\n\nV(ISET) indicates charge current. Monitor w/ADC.\nR3,R5=100K, remove LEDs, if monitoring status w/GPIOs.
Text Notes 5100 5200 0 60 ~ 0
ISET (fast charge current) R6=1K8 (~~500mA).\n\nR4 is required, otherwise no charging.\nILIM (input limit) R4=1K8 (~~850mA).\n\nTMR=open for default timer values.
$EndSCHEMATC