Merge branch 'master' into streaming

This commit is contained in:
schneider42
2017-01-25 11:30:29 +01:00
committed by GitHub
70 changed files with 101924 additions and 59150 deletions

1
.gitignore vendored
View File

@ -5,6 +5,7 @@
*.hex
*.srec
host/build/
host/**/build
# Operating system spew
.DS_Store

3
.gitmodules vendored
View File

@ -1,3 +1,6 @@
[submodule "firmware/libopencm3"]
path = firmware/libopencm3
url = https://github.com/mossmann/libopencm3.git
[submodule "hardware/gsg-kicad-lib"]
path = hardware/gsg-kicad-lib
url = https://github.com/greatscottgadgets/gsg-kicad-lib.git

View File

@ -2,30 +2,53 @@ language: c
cache: apt
sudo: false
dist: trusty
os:
- linux
- osx
compiler:
- gcc
# - clang
- clang
matrix:
exclude:
- os: osx
compiler: gcc
- os: linux
compiler: clang
before_script:
# - wget https://launchpad.net/gcc-arm-embedded/5.0/5-2016-q1-update/+download/gcc-arm-none-eabi-5_3-2016q1-20160330-linux.tar.bz2 -O /tmp/gcc-arm.tar.bz2
# - tar -xvf /tmp/gcc-arm.tar.bz2
# - export PATH=$PWD/gcc-arm-none-eabi-5_3-2016q1/bin:$PATH
- export CFLAGS="-Wall -Wextra -Werror"
before_install:
- if [[ "$TRAVIS_OS_NAME" == "osx" ]]; then brew tap PX4/homebrew-px4; brew update; fi
- if [[ "$TRAVIS_OS_NAME" == "osx" ]]; then brew install libusb fftw gcc-arm-none-eabi dfu-util; fi
# For virtualenv(?) reasons we can't apt-get install python-yaml
- pip install PyYAML
script:
- mkdir host/build
- cd host/build
- cmake ..
- make
# - cd ../../firmware/hackrf_usb
# - mkdir build
# - cd build
# - export CC="arm-none-eabi-gcc"
# - export CXX="arm-none-eabi-g++"
# - cmake ..
# - make
- cd ../../firmware/libopencm3
- make
- cd ../hackrf_usb
- mkdir build
- cd build
- cmake ..
- make
addons:
apt:
sources:
- debian-sid
packages:
- libusb-1.0-0-dev
- libfftw3-dev
- gcc-arm-none-eabi
- libnewlib-arm-none-eabi
- dfu-util

View File

@ -6,7 +6,7 @@ projects. The cpld directory contains HDL source for the CPLD.
The firmware is set up for compilation with the GCC toolchain available here:
https://launchpad.net/gcc-arm-embedded
https://developer.arm.com/open-source/gnu-toolchain/gnu-rm/downloads
Required dependency:
@ -42,15 +42,7 @@ To start up HackRF One in DFU mode, hold down the DFU button while powering it
on or while pressing and releasing the RESET button. Release the DFU button
after the 3V3 LED illuminates.
With dfu-util and dfu-suffix (from the dfu-util package) installed and with the
HackRF operating in DFU mode, you can build firmware for RAM and load it with:
$ cd hackrf_usb
$ mkdir build
$ cd build
$ cmake .. -DRUN_FROM=RAM
$ make hackrf_usb-program
Alternatively you can load a .dfu file from a release package with:
A .dfu file is built by default when building firmware. Alternatively you can
load a known good .dfu file from a release package with:
$ dfu-util --device 1fc9:000c --alt 0 --download hackrf_usb_ram.dfu

View File

@ -36,15 +36,13 @@ int main(void)
led_on(LED2);
led_on(LED3);
for (i = 0; i < 2000000; i++) /* Wait a bit. */
__asm__("nop");
delay(2000000);
led_off(LED1);
led_off(LED2);
led_off(LED3);
for (i = 0; i < 2000000; i++) /* Wait a bit. */
__asm__("nop");
delay(2000000);
}
return 0;

View File

@ -85,6 +85,17 @@ static struct gpio_t gpio_rffc5072_select = GPIO(2, 13);
static struct gpio_t gpio_rffc5072_clock = GPIO(5, 6);
static struct gpio_t gpio_rffc5072_data = GPIO(3, 3);
static struct gpio_t gpio_rffc5072_reset = GPIO(2, 14);
/*
static struct gpio_t gpio_sync_in_a = GPIO(3, 8);
static struct gpio_t gpio_sync_in_b = GPIO(3, 9);
static struct gpio_t gpio_sync_out_a = GPIO(3, 10);
static struct gpio_t gpio_sync_out_b = GPIO(3, 11);
*/
static struct gpio_t gpio_sync_in_a = GPIO(3, 10);
static struct gpio_t gpio_sync_in_b = GPIO(3, 11);
static struct gpio_t gpio_sync_out_a = GPIO(3, 8);
static struct gpio_t gpio_sync_out_b = GPIO(3, 9);
#endif
/* RF LDO control */
@ -841,6 +852,15 @@ void pin_setup(void) {
/* Safe state: start with VAA turned off: */
disable_rf_power();
scu_pinmux(SCU_PINMUX_GPIO3_10, SCU_GPIO_PDN | SCU_CONF_FUNCTION0);
scu_pinmux(SCU_PINMUX_GPIO3_11, SCU_GPIO_PDN | SCU_CONF_FUNCTION0);
gpio_input(&gpio_sync_in_a);
gpio_input(&gpio_sync_in_b);
gpio_output(&gpio_sync_out_a);
gpio_output(&gpio_sync_out_b);
#endif
/* enable input on SCL and SDA pins */
@ -886,3 +906,34 @@ void led_off(const led_t led) {
void led_toggle(const led_t led) {
gpio_toggle(&gpio_led[led]);
}
void hw_sync_syn() {
gpio_set(&gpio_sync_out_a);
}
void hw_sync_stop() {
gpio_clear(&gpio_sync_out_a);
gpio_clear(&gpio_sync_out_b);
}
void hw_sync_ack() {
gpio_set(&gpio_sync_out_b);
}
void hw_sync_copy_state() {
if(gpio_read(&gpio_sync_in_a)) {
gpio_set(&gpio_sync_out_a);
} else {
gpio_clear(&gpio_sync_out_a);
}
if(gpio_read(&gpio_sync_in_b)) {
gpio_set(&gpio_sync_out_b);
} else {
gpio_clear(&gpio_sync_out_b);
}
}
bool hw_sync_ready() {
return (gpio_read(&gpio_sync_in_a) && gpio_read(&gpio_sync_in_b));
}

View File

@ -225,6 +225,11 @@ typedef enum {
TRANSCEIVER_MODE_CPLD_UPDATE = 4
} transceiver_mode_t;
typedef enum {
HW_SYNC_MODE_OFF = 0,
HW_SYNC_MODE_ON = 1,
} hw_sync_mode_t;
void delay(uint32_t duration);
/* TODO: Hide these configurations */
@ -240,6 +245,7 @@ extern w25q80bv_driver_t spi_flash;
extern sgpio_config_t sgpio_config;
extern rf_path_t rf_path;
extern jtag_t jtag_cpld;
extern i2c_bus_t i2c0;
void cpu_clock_init(void);
void cpu_clock_pll1_low_speed(void);
@ -271,6 +277,13 @@ void led_on(const led_t led);
void led_off(const led_t led);
void led_toggle(const led_t led);
void hw_sync_syn();
void hw_sync_stop();
void hw_sync_ack();
bool hw_sync_ready();
void hw_sync_copy_state();
#ifdef __cplusplus
}
#endif

View File

@ -44,17 +44,23 @@ void i2c_lpc_transfer(i2c_bus_t* const bus,
uint8_t* const data_rx, const size_t count_rx
) {
const uint32_t port = (uint32_t)bus->obj;
i2c_tx_start(port);
i2c_tx_byte(port, (slave_address << 1) | I2C_WRITE);
for(size_t i=0; i<count_tx; i++) {
i2c_tx_byte(port, data_tx[i]);
size_t i;
bool ack = false;
if (data_tx && (count_tx > 0)) {
i2c_tx_start(port);
i2c_tx_byte(port, (slave_address << 1) | I2C_WRITE);
for(i=0; i<count_tx; i++) {
i2c_tx_byte(port, data_tx[i]);
}
}
if( data_rx ) {
if (data_rx && (count_rx > 0)) {
i2c_tx_start(port);
i2c_tx_byte(port, (slave_address << 1) | I2C_READ);
for(size_t i=0; i<count_rx; i++) {
data_rx[i] = i2c_rx_byte(port);
for(i=0; i<count_rx; i++) {
/* ACK each byte except the last */
ack = (i!=count_rx-1);
data_rx[i] = i2c_rx_byte(port, ack);
}
}

146
firmware/common/operacake.c Normal file
View File

@ -0,0 +1,146 @@
/*
* Copyright 2016 Dominic Spill <dominicgs@gmail.com>
*
* This file is part of HackRF.
*
* 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 "operacake.h"
#include "hackrf_core.h"
#define OPERACAKE_PIN_OE(x) (x<<7)
#define OPERACAKE_PIN_U2CTRL1(x) (x<<6)
#define OPERACAKE_PIN_U2CTRL0(x) (x<<5)
#define OPERACAKE_PIN_U3CTRL1(x) (x<<4)
#define OPERACAKE_PIN_U3CTRL0(x) (x<<3)
#define OPERACAKE_PIN_U1CTRL(x) (x<<2)
#define OPERACAKE_PIN_LEDEN2(x) (x<<1)
#define OPERACAKE_PIN_LEDEN(x) (x<<0)
#define OPERACAKE_PORT_A1 (OPERACAKE_PIN_U2CTRL0(0) | OPERACAKE_PIN_U2CTRL1(0))
#define OPERACAKE_PORT_A2 (OPERACAKE_PIN_U2CTRL0(1) | OPERACAKE_PIN_U2CTRL1(0))
#define OPERACAKE_PORT_A3 (OPERACAKE_PIN_U2CTRL0(0) | OPERACAKE_PIN_U2CTRL1(1))
#define OPERACAKE_PORT_A4 (OPERACAKE_PIN_U2CTRL0(1) | OPERACAKE_PIN_U2CTRL1(1))
#define OPERACAKE_PORT_B1 (OPERACAKE_PIN_U3CTRL0(0) | OPERACAKE_PIN_U3CTRL1(0))
#define OPERACAKE_PORT_B2 (OPERACAKE_PIN_U3CTRL0(1) | OPERACAKE_PIN_U3CTRL1(0))
#define OPERACAKE_PORT_B3 (OPERACAKE_PIN_U3CTRL0(0) | OPERACAKE_PIN_U3CTRL1(1))
#define OPERACAKE_PORT_B4 (OPERACAKE_PIN_U3CTRL0(1) | OPERACAKE_PIN_U3CTRL1(1))
#define OPERACAKE_SAMESIDE OPERACAKE_PIN_U1CTRL(1)
#define OPERACAKE_CROSSOVER OPERACAKE_PIN_U1CTRL(0)
#define OPERACAKE_EN_LEDS (OPERACAKE_PIN_LEDEN2(1) | OPERACAKE_PIN_LEDEN2(0))
#define OPERACAKE_GPIO_EN OPERACAKE_PIN_OE(0)
#define OPERACAKE_GPIO_DISABLE OPERACAKE_PIN_OE(1)
#define OPERACAKE_REG_INPUT 0x00
#define OPERACAKE_REG_OUTPUT 0x01
#define OPERACAKE_REG_POLARITY 0x02
#define OPERACAKE_REG_CONFIG 0x03
#define OPERACAKE_DEFAULT_OUTPUT (OPERACAKE_GPIO_DISABLE | OPERACAKE_SAMESIDE \
| OPERACAKE_PORT_A1 | OPERACAKE_PORT_B1 \
| OPERACAKE_EN_LEDS)
#define OPERACAKE_CONFIG_ALL_OUTPUT (0x00)
#define OPERACAKE_DEFAULT_ADDRESS 0x18
i2c_bus_t* const oc_bus = &i2c0;
uint8_t operacake_boards[8] = {0,0,0,0,0,0,0,0};
/* read single register */
uint8_t operacake_read_reg(i2c_bus_t* const bus, uint8_t address, uint8_t reg) {
const uint8_t data_tx[] = { reg };
uint8_t data_rx[] = { 0x00 };
i2c_bus_transfer(bus, address, data_tx, 1, data_rx, 1);
return data_rx[0];
}
/* Write to one of the PCA9557 registers */
void operacake_write_reg(i2c_bus_t* const bus, uint8_t address, uint8_t reg, uint8_t value) {
const uint8_t data[] = {reg, value};
i2c_bus_transfer(bus, address, data, 2, NULL, 0);
}
uint8_t operacake_init(void) {
uint8_t reg, addr, i, j = 0;
/* Find connected operacakes */
for(i=0; i<8; i++) {
addr = OPERACAKE_DEFAULT_ADDRESS | i;
operacake_write_reg(oc_bus, addr, OPERACAKE_REG_OUTPUT,
OPERACAKE_DEFAULT_OUTPUT);
operacake_write_reg(oc_bus, addr, OPERACAKE_REG_CONFIG,
OPERACAKE_CONFIG_ALL_OUTPUT);
reg = operacake_read_reg(oc_bus, addr, OPERACAKE_REG_CONFIG);
if(reg==OPERACAKE_CONFIG_ALL_OUTPUT)
operacake_boards[j++] = addr;
}
return 0;
}
uint8_t port_to_pins(uint8_t port) {
switch(port) {
case OPERACAKE_PA1:
return OPERACAKE_PORT_A1;
case OPERACAKE_PA2:
return OPERACAKE_PORT_A2;
case OPERACAKE_PA3:
return OPERACAKE_PORT_A3;
case OPERACAKE_PA4:
return OPERACAKE_PORT_A4;
case OPERACAKE_PB1:
return OPERACAKE_PORT_B1;
case OPERACAKE_PB2:
return OPERACAKE_PORT_B2;
case OPERACAKE_PB3:
return OPERACAKE_PORT_B3;
case OPERACAKE_PB4:
return OPERACAKE_PORT_B4;
}
return 0xFF;
}
uint8_t operacake_set_ports(uint8_t address, uint8_t PA, uint8_t PB) {
uint8_t side, pa, pb, reg;
/* Start with some error checking,
* which should have been done either
* on the host or elsewhere in firmware
*/
if((PA > OPERACAKE_PB4) || (PB > OPERACAKE_PB4)) {
return 1;
}
/* Check which side PA and PB are on */
if(((PA <= OPERACAKE_PA4) && (PB <= OPERACAKE_PA4))
|| ((PA > OPERACAKE_PA4) && (PB > OPERACAKE_PA4))) {
return 1;
}
if(PA > OPERACAKE_PA4)
side = OPERACAKE_CROSSOVER;
else
side = OPERACAKE_SAMESIDE;
pa = port_to_pins(PA);
pb = port_to_pins(PB);
reg = (OPERACAKE_GPIO_DISABLE | side
| pa | pb | OPERACAKE_EN_LEDS);
operacake_write_reg(oc_bus, address, OPERACAKE_REG_OUTPUT, reg);
return 0;
}

View File

@ -0,0 +1,53 @@
/*
* Copyright 2016 Dominic Spill <dominicgs@gmail.com>
*
* This file is part of HackRF.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __OPERACAKE_H
#define __OPERACAKE_H
#ifdef __cplusplus
extern "C"
{
#endif
#include <stdint.h>
#include "i2c_bus.h"
#define OPERACAKE_PA1 0
#define OPERACAKE_PA2 1
#define OPERACAKE_PA3 2
#define OPERACAKE_PA4 3
#define OPERACAKE_PB1 4
#define OPERACAKE_PB2 5
#define OPERACAKE_PB3 6
#define OPERACAKE_PB4 7
/* Up to 8 Operacake boards can be used with one HackRF */
extern uint8_t operacake_boards[8];
uint8_t operacake_init(void);
uint8_t operacake_set_ports(uint8_t address, uint8_t PA, uint8_t PB);
#ifdef __cplusplus
}
#endif
#endif /* __OPERACAKE_H */

View File

@ -117,6 +117,10 @@ void rffc5071_setup(rffc5071_driver_t* const drv)
/* GPOs are active at all times */
set_RFFC5071_GATE(drv, 1);
/* Output LOCK status on GPO4 and enable lock detect */
set_RFFC5071_LOCK(drv, 1);
set_RFFC5071_LDEN(drv, 1);
rffc5071_regs_commit(drv);
}
@ -254,13 +258,6 @@ uint64_t rffc5071_config_synth_int(rffc5071_driver_t* const drv, uint16_t lo) {
tune_freq_hz = (REF_FREQ * (tmp_n >> 5ULL) * fbkdiv * FREQ_ONE_MHZ)
/ (lodiv * (1 << 24ULL));
/* Path 1 */
set_RFFC5071_P1LODIV(drv, n_lo);
set_RFFC5071_P1N(drv, n);
set_RFFC5071_P1PRESC(drv, fbkdiv >> 1);
set_RFFC5071_P1NMSB(drv, p1nmsb);
set_RFFC5071_P1NLSB(drv, p1nlsb);
/* Path 2 */
set_RFFC5071_P2LODIV(drv, n_lo);
set_RFFC5071_P2N(drv, n);

View File

@ -94,10 +94,7 @@ void rffc5071_spi_stop(spi_bus_t* const bus) {
static void rffc5071_spi_serial_delay(spi_bus_t* const bus) {
(void)bus;
volatile uint32_t i;
for (i = 0; i < 2; i++)
__asm__("nop");
__asm__("nop");
}
static void rffc5071_spi_sck(spi_bus_t* const bus) {

7
firmware/dfu.py Normal file
View File

@ -0,0 +1,7 @@
import os.path
import struct
with open("_header.bin", "wb") as f:
x = struct.pack('<H', os.path.getsize('hackrf_usb_dfu.bin') // 512 + 1)
y = [0xda, 0xff, x[0], x[1], 0xff, 0xff, 0xff, 0xff]
f.write(bytearray(y))

View File

@ -3,6 +3,7 @@
# Copyright 2012 Michael Ossmann <mike@ossmann.com>
# Copyright 2012 Benjamin Vernoux <titanmkd@gmail.com>
# Copyright 2012 Jared Boone <jared@sharebrained.com>
# Copyright 2016 Dominic Spill <dominicgs@gmail.com>
#
# This file is part of HackRF.
#
@ -51,10 +52,6 @@ if(NOT DEFINED BOARD)
set(BOARD HACKRF_ONE)
endif()
if(NOT DEFINED RUN_FROM)
set(RUN_FROM SPIFI)
endif()
if(BOARD STREQUAL "HACKRF_ONE")
set(MCU_PARTNO LPC4320)
else()
@ -65,15 +62,11 @@ if(NOT DEFINED SRC_M0)
set(SRC_M0 "${PATH_HACKRF_FIRMWARE_COMMON}/m0_sleep.c")
endif()
SET(HACKRF_OPTS "-D${BOARD} -DLPC43XX -D${MCU_PARTNO} -DTX_ENABLE -D'VERSION_STRING=\"git-${VERSION}\"' -DRUN_FROM=${RUN_FROM}")
SET(HACKRF_OPTS "-D${BOARD} -DLPC43XX -D${MCU_PARTNO} -DTX_ENABLE -D'VERSION_STRING=\"git-${VERSION}\"'")
SET(LDSCRIPT_M4 "-T${PATH_HACKRF_FIRMWARE_COMMON}/${MCU_PARTNO}_M4_memory.ld")
if( RUN_FROM STREQUAL "RAM")
SET(LDSCRIPT_M4 "${LDSCRIPT_M4} -Tlibopencm3_lpc43xx.ld")
else()
SET(LDSCRIPT_M4 "${LDSCRIPT_M4} -Tlibopencm3_lpc43xx_rom_to_ram.ld")
endif()
SET(LDSCRIPT_M4 "${LDSCRIPT_M4} -T${PATH_HACKRF_FIRMWARE_COMMON}/LPC43xx_M4_M0_image_from_text.ld")
SET(LDSCRIPT_M4 "-T${PATH_HACKRF_FIRMWARE_COMMON}/${MCU_PARTNO}_M4_memory.ld -Tlibopencm3_lpc43xx_rom_to_ram.ld -T${PATH_HACKRF_FIRMWARE_COMMON}/LPC43xx_M4_M0_image_from_text.ld")
SET(LDSCRIPT_M4_DFU "-T${PATH_HACKRF_FIRMWARE_COMMON}/${MCU_PARTNO}_M4_memory.ld -Tlibopencm3_lpc43xx.ld -T${PATH_HACKRF_FIRMWARE_COMMON}/LPC43xx_M4_M0_image_from_text.ld")
SET(LDSCRIPT_M0 "-T${PATH_HACKRF_FIRMWARE_COMMON}/LPC43xx_M0_memory.ld -Tlibopencm3_lpc43xx_m0.ld")
@ -93,6 +86,7 @@ SET(CPUFLAGS_M4 "-mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16")
SET(CFLAGS_M4 "-std=gnu99 ${CFLAGS_COMMON} ${CPUFLAGS_M4} -DLPC43XX_M4")
SET(CXXFLAGS_M4 "-std=gnu++0x ${CFLAGS_COMMON} ${CPUFLAGS_M4} -DLPC43XX_M4")
SET(LDFLAGS_M4 "${LDFLAGS_COMMON} ${CPUFLAGS_M4} ${LDSCRIPT_M4} -Xlinker -Map=m4.map")
SET(LDFLAGS_M4_DFU "${LDFLAGS_COMMON} ${CPUFLAGS_M4} ${LDSCRIPT_M4_DFU} -Xlinker -Map=m4.map")
set(BUILD_SHARED_LIBS OFF)
@ -100,6 +94,27 @@ include_directories("${LIBOPENCM3}/include/")
include_directories("${PATH_HACKRF_FIRMWARE_COMMON}")
macro(DeclareTargets)
SET(SRC_M4
${SRC_M4}
${PATH_HACKRF_FIRMWARE_COMMON}/hackrf_core.c
${PATH_HACKRF_FIRMWARE_COMMON}/sgpio.c
${PATH_HACKRF_FIRMWARE_COMMON}/rf_path.c
${PATH_HACKRF_FIRMWARE_COMMON}/si5351c.c
${PATH_HACKRF_FIRMWARE_COMMON}/max2837.c
${PATH_HACKRF_FIRMWARE_COMMON}/max2837_target.c
${PATH_HACKRF_FIRMWARE_COMMON}/max5864.c
${PATH_HACKRF_FIRMWARE_COMMON}/max5864_target.c
${PATH_HACKRF_FIRMWARE_COMMON}/rffc5071.c
${PATH_HACKRF_FIRMWARE_COMMON}/i2c_bus.c
${PATH_HACKRF_FIRMWARE_COMMON}/i2c_lpc.c
${PATH_HACKRF_FIRMWARE_COMMON}/rffc5071_spi.c
${PATH_HACKRF_FIRMWARE_COMMON}/w25q80bv.c
${PATH_HACKRF_FIRMWARE_COMMON}/w25q80bv_target.c
${PATH_HACKRF_FIRMWARE_COMMON}/spi_bus.c
${PATH_HACKRF_FIRMWARE_COMMON}/spi_ssp.c
${PATH_HACKRF_FIRMWARE_COMMON}/gpio_lpc.c
)
configure_file(
${PATH_HACKRF_FIRMWARE_COMMON}/m0_bin.s.cmake
m0_bin.s
@ -130,29 +145,13 @@ macro(DeclareTargets)
COMMAND ${CMAKE_OBJCOPY} -Obinary ${PROJECT_NAME}_m0.elf ${PROJECT_NAME}_m0.bin
)
add_executable(${PROJECT_NAME}.elf
${SRC_M4}
${PATH_HACKRF_FIRMWARE_COMMON}/hackrf_core.c
${PATH_HACKRF_FIRMWARE_COMMON}/sgpio.c
${PATH_HACKRF_FIRMWARE_COMMON}/rf_path.c
${PATH_HACKRF_FIRMWARE_COMMON}/si5351c.c
${PATH_HACKRF_FIRMWARE_COMMON}/max2837.c
${PATH_HACKRF_FIRMWARE_COMMON}/max2837_target.c
${PATH_HACKRF_FIRMWARE_COMMON}/max5864.c
${PATH_HACKRF_FIRMWARE_COMMON}/max5864_target.c
${PATH_HACKRF_FIRMWARE_COMMON}/rffc5071.c
${PATH_HACKRF_FIRMWARE_COMMON}/i2c_bus.c
${PATH_HACKRF_FIRMWARE_COMMON}/i2c_lpc.c
${PATH_HACKRF_FIRMWARE_COMMON}/rffc5071_spi.c
${PATH_HACKRF_FIRMWARE_COMMON}/w25q80bv.c
${PATH_HACKRF_FIRMWARE_COMMON}/w25q80bv_target.c
${PATH_HACKRF_FIRMWARE_COMMON}/spi_bus.c
${PATH_HACKRF_FIRMWARE_COMMON}/spi_ssp.c
${PATH_HACKRF_FIRMWARE_COMMON}/gpio_lpc.c
m0_bin.s
)
# Object files to be linked for both DFU and SPI flash versions
add_library(${PROJECT_NAME}_objects OBJECT ${SRC_M4} m0_bin.s)
set_target_properties(${PROJECT_NAME}_objects PROPERTIES COMPILE_FLAGS "${CFLAGS_M4}")
add_dependencies(${PROJECT_NAME}_objects ${PROJECT_NAME}_m0.bin)
add_dependencies(${PROJECT_NAME}.elf ${PROJECT_NAME}_m0.bin)
# SPI flash version
add_executable(${PROJECT_NAME}.elf $<TARGET_OBJECTS:${PROJECT_NAME}_objects>)
target_link_libraries(
${PROJECT_NAME}.elf
@ -162,22 +161,40 @@ macro(DeclareTargets)
m
)
set_target_properties(${PROJECT_NAME}.elf PROPERTIES COMPILE_FLAGS "${CFLAGS_M4}")
set_target_properties(${PROJECT_NAME}.elf PROPERTIES LINK_FLAGS "${LDFLAGS_M4}")
add_custom_target(
${PROJECT_NAME}.bin
${PROJECT_NAME}.bin ALL
DEPENDS ${PROJECT_NAME}.elf
COMMAND ${CMAKE_OBJCOPY} -Obinary ${PROJECT_NAME}.elf ${PROJECT_NAME}.bin
)
# DFU - using a differnet LD script to run directly from RAM
add_executable(${PROJECT_NAME}_dfu.elf $<TARGET_OBJECTS:${PROJECT_NAME}_objects>)
target_link_libraries(
${PROJECT_NAME}_dfu.elf
c
nosys
opencm3_lpc43xx
m
)
set_target_properties(${PROJECT_NAME}_dfu.elf PROPERTIES LINK_FLAGS "${LDFLAGS_M4_DFU}")
add_custom_target(
${PROJECT_NAME}_dfu.bin
DEPENDS ${PROJECT_NAME}_dfu.elf
COMMAND ${CMAKE_OBJCOPY} -Obinary ${PROJECT_NAME}_dfu.elf ${PROJECT_NAME}_dfu.bin
)
add_custom_target(
${PROJECT_NAME}.dfu ${DFU_ALL}
DEPENDS ${PROJECT_NAME}.bin
DEPENDS ${PROJECT_NAME}_dfu.bin
COMMAND rm -f _tmp.dfu _header.bin
COMMAND cp ${PROJECT_NAME}.bin _tmp.dfu
COMMAND cp ${PROJECT_NAME}_dfu.bin _tmp.dfu
COMMAND ${DFU_COMMAND}
COMMAND python -c \"import os.path\; import struct\; print\('0000000: da ff ' + ' '.join\(map\(lambda s: '%02x' % ord\(s\), struct.pack\('<H', os.path.getsize\('${PROJECT_NAME}.bin'\) / 512 + 1\)\)\) + ' ff ff ff ff'\)\" | xxd -g1 -r > _header.bin
COMMAND python ../../dfu.py
COMMAND cat _header.bin _tmp.dfu >${PROJECT_NAME}.dfu
COMMAND rm -f _tmp.dfu _header.bin
)

View File

@ -42,6 +42,9 @@ set(SRC_M4
usb_api_register.c
usb_api_spiflash.c
usb_api_transceiver.c
"${PATH_HACKRF_FIRMWARE_COMMON}/operacake.c"
usb_api_operacake.c
usb_api_sweep.c
"${PATH_HACKRF_FIRMWARE_COMMON}/usb_queue.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/fault_handler.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/cpld_jtag.c"

View File

@ -22,12 +22,12 @@
#include <stddef.h>
#include <libopencm3/cm3/vector.h>
#include <libopencm3/lpc43xx/m4/nvic.h>
#include <streaming.h>
#include "tuning.h"
#include "usb.h"
#include "usb_standard_request.h"
@ -40,75 +40,12 @@
#include "usb_api_cpld.h"
#include "usb_api_register.h"
#include "usb_api_spiflash.h"
#include "usb_api_operacake.h"
#include "operacake.h"
#include "usb_api_sweep.h"
#include "usb_api_transceiver.h"
#include "sgpio_isr.h"
#include "usb_bulk_buffer.h"
static volatile transceiver_mode_t _transceiver_mode = TRANSCEIVER_MODE_OFF;
void set_transceiver_mode(const transceiver_mode_t new_transceiver_mode) {
baseband_streaming_disable(&sgpio_config);
usb_endpoint_disable(&usb_endpoint_bulk_in);
usb_endpoint_disable(&usb_endpoint_bulk_out);
_transceiver_mode = new_transceiver_mode;
if( _transceiver_mode == TRANSCEIVER_MODE_RX ) {
led_off(LED3);
led_on(LED2);
usb_endpoint_init(&usb_endpoint_bulk_in);
rf_path_set_direction(&rf_path, RF_PATH_DIRECTION_RX);
vector_table.irq[NVIC_SGPIO_IRQ] = sgpio_isr_rx;
} else if (_transceiver_mode == TRANSCEIVER_MODE_TX) {
led_off(LED2);
led_on(LED3);
usb_endpoint_init(&usb_endpoint_bulk_out);
rf_path_set_direction(&rf_path, RF_PATH_DIRECTION_TX);
vector_table.irq[NVIC_SGPIO_IRQ] = sgpio_isr_tx;
} else {
led_off(LED2);
led_off(LED3);
rf_path_set_direction(&rf_path, RF_PATH_DIRECTION_OFF);
vector_table.irq[NVIC_SGPIO_IRQ] = sgpio_isr_rx;
}
if( _transceiver_mode != TRANSCEIVER_MODE_OFF ) {
si5351c_activate_best_clock_source(&clock_gen);
baseband_streaming_enable(&sgpio_config);
}
}
transceiver_mode_t transceiver_mode(void) {
return _transceiver_mode;
}
usb_request_status_t usb_vendor_request_set_transceiver_mode(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
if( stage == USB_TRANSFER_STAGE_SETUP ) {
switch( endpoint->setup.value ) {
case TRANSCEIVER_MODE_OFF:
case TRANSCEIVER_MODE_RX:
case TRANSCEIVER_MODE_TX:
set_transceiver_mode(endpoint->setup.value);
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
case TRANSCEIVER_MODE_CPLD_UPDATE:
usb_endpoint_init(&usb_endpoint_bulk_out);
start_cpld_update = true;
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
default:
return USB_REQUEST_STATUS_STALL;
}
} else {
return USB_REQUEST_STATUS_OK;
}
}
static const usb_request_handler_fn vendor_request_handler[] = {
NULL,
usb_vendor_request_set_transceiver_mode,
@ -140,6 +77,10 @@ static const usb_request_handler_fn vendor_request_handler[] = {
#endif
usb_vendor_request_set_freq_explicit,
usb_vendor_request_read_wcid, // USB_WCID_VENDOR_REQ
usb_vendor_request_init_sweep,
usb_vendor_request_operacake_get_boards,
usb_vendor_request_operacake_set_ports,
usb_vendor_request_set_hw_sync_mode
};
static const uint32_t vendor_request_handler_count =
@ -237,13 +178,23 @@ int main(void) {
usb_run(&usb_device);
rf_path_init(&rf_path);
operacake_init();
unsigned int phase = 0;
while(true) {
// Check whether we need to initiate a CPLD update
if (start_cpld_update)
cpld_update();
// Check whether we need to initiate sweep mode
if (start_sweep_mode) {
start_sweep_mode = false;
sweep_mode();
}
start_streaming_on_hw_sync();
// Set up IN transfer of buffer 0.
if ( usb_bulk_buffer_offset >= 16384
&& phase == 1

View File

@ -0,0 +1,49 @@
/*
* Copyright 2016 Dominic Spill <dominicgs@gmail.com>
*
* This file is part of HackRF.
*
* 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 "usb_api_operacake.h"
#include "usb_queue.h"
#include <operacake.h>
usb_request_status_t usb_vendor_request_operacake_get_boards(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
if (stage == USB_TRANSFER_STAGE_SETUP) {
usb_transfer_schedule_block(endpoint->in, operacake_boards, 8, NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
}
return USB_REQUEST_STATUS_OK;
}
usb_request_status_t usb_vendor_request_operacake_set_ports(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
uint8_t address, port_a, port_b;
address = endpoint->setup.value & 0xFF;
port_a = endpoint->setup.index & 0xFF;
port_b = (endpoint->setup.index >> 8) & 0xFF;
if (stage == USB_TRANSFER_STAGE_SETUP) {
operacake_set_ports(address, port_a, port_b);
usb_transfer_schedule_ack(endpoint->in);
}
return USB_REQUEST_STATUS_OK;
}

View File

@ -0,0 +1,34 @@
/*
* Copyright 2016 Dominic Spill <dominicgs@gmail.com>
*
* This file is part of HackRF.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __USB_API_OPERACAKE_H__
#define __USB_API_OPERACAKE_H__
#include <usb_type.h>
#include <usb_request.h>
usb_request_status_t usb_vendor_request_operacake_get_boards(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_operacake_set_ports(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
#endif /* end of include guard: __USB_API_OPERACAKE_H__ */

View File

@ -0,0 +1,109 @@
/*
* Copyright 2016 Mike Walters, Dominic Spill
*
* This file is part of HackRF.
*
* 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 "usb_api_sweep.h"
#include "usb_queue.h"
#include <stddef.h>
#include <hackrf_core.h>
#include "usb_api_transceiver.h"
#include "usb_bulk_buffer.h"
#include "tuning.h"
#include "usb_endpoint.h"
#define MIN(x,y) ((x)<(y)?(x):(y))
#define MAX(x,y) ((x)>(y)?(x):(y))
#define FREQ_GRANULARITY 1000000
#define MIN_FREQ 1
#define MAX_FREQ 6000
#define MAX_FREQ_COUNT 1000
volatile bool start_sweep_mode = false;
static uint64_t sweep_freq;
bool odd = true;
static uint16_t frequencies[MAX_FREQ_COUNT];
static uint16_t frequency_count = 0;
static uint32_t dwell_blocks = 0;
usb_request_status_t usb_vendor_request_init_sweep(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
uint32_t dwell_time;
if (stage == USB_TRANSFER_STAGE_SETUP) {
dwell_time = (endpoint->setup.index << 16) | endpoint->setup.value;
dwell_blocks = dwell_time / 0x4000;
frequency_count = endpoint->setup.length / sizeof(uint16_t);
usb_transfer_schedule_block(endpoint->out, &frequencies,
endpoint->setup.length, NULL, NULL);
} else if (stage == USB_TRANSFER_STAGE_DATA) {
sweep_freq = frequencies[0];
set_freq(sweep_freq*FREQ_GRANULARITY);
start_sweep_mode = true;
usb_transfer_schedule_ack(endpoint->in);
}
return USB_REQUEST_STATUS_OK;
}
void sweep_mode(void) {
unsigned int blocks_queued = 0;
unsigned int phase = 0;
unsigned int ifreq = 0;
uint8_t *buffer;
bool transfer = false;
while(transceiver_mode() != TRANSCEIVER_MODE_OFF) {
// Set up IN transfer of buffer 0.
if ( usb_bulk_buffer_offset >= 16384 && phase == 1) {
transfer = true;
buffer = &usb_bulk_buffer[0x0000];
phase = 0;
blocks_queued++;
}
// Set up IN transfer of buffer 1.
if ( usb_bulk_buffer_offset < 16384 && phase == 0) {
transfer = true;
buffer = &usb_bulk_buffer[0x4000];
phase = 1;
blocks_queued++;
}
if (transfer) {
*(uint16_t*)buffer = 0x7F7F;
*(uint16_t*)(buffer+2) = sweep_freq;
usb_transfer_schedule_block(
&usb_endpoint_bulk_in,
buffer,
0x4000,
NULL, NULL
);
transfer = false;
}
if (blocks_queued >= dwell_blocks) {
if(++ifreq >= frequency_count)
ifreq = 0;
sweep_freq = frequencies[ifreq];
set_freq(sweep_freq*FREQ_GRANULARITY);
blocks_queued = 0;
}
}
}

View File

@ -0,0 +1,36 @@
/*
* Copyright 2016 Mike Walters, Dominic Spill
*
* This file is part of HackRF.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __USB_API_SCAN_H__
#define __USB_API_SCAN_H__
#include <stdbool.h>
#include <usb_type.h>
#include <usb_request.h>
extern volatile bool start_sweep_mode;
usb_request_status_t usb_vendor_request_init_sweep(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
void sweep_mode(void);
#endif /* __USB_API_SPCAN_H__ */

View File

@ -22,9 +22,16 @@
#include "usb_api_transceiver.h"
#include <libopencm3/cm3/vector.h>
#include <libopencm3/lpc43xx/m4/nvic.h>
#include "sgpio_isr.h"
#include "usb_api_cpld.h" // Remove when CPLD update is handled elsewhere
#include <max2837.h>
#include <rf_path.h>
#include <tuning.h>
#include <streaming.h>
#include <usb.h>
#include <usb_queue.h>
@ -221,3 +228,105 @@ usb_request_status_t usb_vendor_request_set_freq_explicit(
return USB_REQUEST_STATUS_OK;
}
}
static volatile transceiver_mode_t _transceiver_mode = TRANSCEIVER_MODE_OFF;
static volatile hw_sync_mode_t _hw_sync_mode = HW_SYNC_MODE_OFF;
void set_hw_sync_mode(const hw_sync_mode_t new_hw_sync_mode) {
_hw_sync_mode = new_hw_sync_mode;
}
transceiver_mode_t transceiver_mode(void) {
return _transceiver_mode;
}
void set_transceiver_mode(const transceiver_mode_t new_transceiver_mode) {
baseband_streaming_disable(&sgpio_config);
usb_endpoint_disable(&usb_endpoint_bulk_in);
usb_endpoint_disable(&usb_endpoint_bulk_out);
_transceiver_mode = new_transceiver_mode;
if( _transceiver_mode == TRANSCEIVER_MODE_RX ) {
led_off(LED3);
led_on(LED2);
usb_endpoint_init(&usb_endpoint_bulk_in);
rf_path_set_direction(&rf_path, RF_PATH_DIRECTION_RX);
vector_table.irq[NVIC_SGPIO_IRQ] = sgpio_isr_rx;
} else if (_transceiver_mode == TRANSCEIVER_MODE_TX) {
led_off(LED2);
led_on(LED3);
usb_endpoint_init(&usb_endpoint_bulk_out);
rf_path_set_direction(&rf_path, RF_PATH_DIRECTION_TX);
vector_table.irq[NVIC_SGPIO_IRQ] = sgpio_isr_tx;
} else {
led_off(LED2);
led_off(LED3);
rf_path_set_direction(&rf_path, RF_PATH_DIRECTION_OFF);
vector_table.irq[NVIC_SGPIO_IRQ] = sgpio_isr_rx;
hw_sync_stop();
}
hw_sync_stop();
if( _transceiver_mode != TRANSCEIVER_MODE_OFF ) {
si5351c_activate_best_clock_source(&clock_gen);
if( _hw_sync_mode != HW_SYNC_MODE_OFF) {
hw_sync_syn();
} else {
baseband_streaming_enable(&sgpio_config);
}
}
}
usb_request_status_t usb_vendor_request_set_transceiver_mode(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage)
{
if( stage == USB_TRANSFER_STAGE_SETUP ) {
switch( endpoint->setup.value ) {
case TRANSCEIVER_MODE_OFF:
case TRANSCEIVER_MODE_RX:
case TRANSCEIVER_MODE_TX:
set_transceiver_mode(endpoint->setup.value);
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
case TRANSCEIVER_MODE_CPLD_UPDATE:
usb_endpoint_init(&usb_endpoint_bulk_out);
start_cpld_update = true;
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
default:
return USB_REQUEST_STATUS_STALL;
}
} else {
return USB_REQUEST_STATUS_OK;
}
}
usb_request_status_t usb_vendor_request_set_hw_sync_mode(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage)
{
if( stage == USB_TRANSFER_STAGE_SETUP ) {
set_hw_sync_mode(endpoint->setup.value);
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
} else {
return USB_REQUEST_STATUS_OK;
}
}
void start_streaming_on_hw_sync()
{
if( _hw_sync_mode != HW_SYNC_MODE_OFF) {
while(!hw_sync_ready()) { }
hw_sync_ack();
led_on(LED3);
baseband_streaming_enable(&sgpio_config);
}
}

View File

@ -27,6 +27,7 @@
#include <usb_type.h>
#include <usb_request.h>
void set_hw_sync_mode(const hw_sync_mode_t new_hw_sync_mode);
usb_request_status_t usb_vendor_request_set_transceiver_mode(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage);
@ -52,5 +53,11 @@ usb_request_status_t usb_vendor_request_set_antenna_enable(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_set_freq_explicit(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_set_hw_sync_mode(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
transceiver_mode_t transceiver_mode(void);
void set_transceiver_mode(const transceiver_mode_t new_transceiver_mode);
void start_streaming_on_hw_sync();
#endif/*__USB_API_TRANSCEIVER_H__*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,4 @@
(fp_lib_table
(lib (name hackrf)(type Legacy)(uri ${KIPRJMOD}/../kicad/hackrf.mod)(options "")(descr ""))
(lib (name gsg-modules)(type KiCad)(uri ${KIPRJMOD}/../gsg-kicad-lib/gsg-modules.pretty)(options "")(descr ""))
)

File diff suppressed because it is too large Load Diff

View File

@ -1,4 +1,4 @@
EESchema-LIBRARY Version 2.3 Date: Thu Feb 13 12:23:41 2014
EESchema-LIBRARY Version 2.3
#encoding utf-8
#
# +1.8V
@ -6,8 +6,8 @@ EESchema-LIBRARY Version 2.3 Date: Thu Feb 13 12:23:41 2014
DEF +1.8V #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 140 20 H I C CNN
F1 "+1.8V" 0 110 30 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
ALIAS 1V8
DRAW
P 3 0 0 0 0 0 0 40 0 40 N
@ -21,8 +21,8 @@ ENDDEF
DEF BALUN T 0 40 Y N 1 F N
F0 "T" 0 250 70 H V C CNN
F1 "BALUN" 0 -300 70 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
A -100 -150 50 899 1 0 1 0 N -100 -100 -50 -150
A -100 -150 50 -1 -899 0 1 0 N -50 -150 -100 -199
@ -55,8 +55,8 @@ ENDDEF
DEF BALUN-B0310J50100AHF T 0 40 Y N 1 F N
F0 "T" 0 200 70 H V C CNN
F1 "BALUN-B0310J50100AHF" 0 -150 70 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
A -150 -50 50 1 1799 0 1 0 N -100 -50 -200 -50
A -150 100 50 -1799 -1 0 1 0 N -200 100 -100 100
@ -77,20 +77,22 @@ ENDDEF
# C
#
DEF C C 0 10 N Y 1 F N
F0 "C" 50 100 50 H V L CNN
F1 "C" 50 -100 50 H V L CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F0 "C" 25 100 50 H V L CNN
F1 "C" 25 -100 50 H V L CNN
F2 "" 38 -150 30 H V C CNN
F3 "" 0 0 60 H V C CNN
$FPLIST
SM*
C?
C1-1
C_????_*
C_????
SMD*_c
Capacitor*
$ENDFPLIST
DRAW
P 2 0 1 20 -100 -30 100 -30 N
P 2 0 1 20 -100 30 100 30 N
X ~ 1 0 200 170 D 40 40 1 1 P
X ~ 2 0 -200 170 U 40 40 1 1 P
P 2 0 1 20 -80 -30 80 -30 N
P 2 0 1 20 -80 30 80 30 N
X ~ 1 0 150 110 D 40 40 1 1 P
X ~ 2 0 -150 110 U 40 40 1 1 P
ENDDRAW
ENDDEF
#
@ -99,8 +101,8 @@ ENDDEF
DEF ~CONN_1 P 0 30 N N 1 F N
F0 "P" 80 0 40 H V L CNN
F1 "CONN_1" 0 55 30 H I C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
C 0 0 31 0 1 0 N
P 2 0 1 0 -30 0 -50 0 N
@ -113,8 +115,8 @@ ENDDEF
DEF CONN_10X2 P 0 10 Y N 1 F N
F0 "P" 0 550 60 H V C CNN
F1 "CONN_10X2" 0 -100 50 V V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -100 500 100 -500 0 1 0 f
X P1 1 -400 450 300 R 60 30 1 1 P I
@ -145,8 +147,8 @@ ENDDEF
DEF CONN_11X2 P 0 10 Y N 1 F N
F0 "P" 0 600 60 H V C CNN
F1 "CONN_11X2" 0 0 50 V V C CNN
F2 "~" 0 -250 60 H V C CNN
F3 "~" 0 -250 60 H V C CNN
F2 "" 0 -250 60 H V C CNN
F3 "" 0 -250 60 H V C CNN
DRAW
S -100 550 100 -550 0 1 0 N
S 1200 650 1200 650 0 1 0 N
@ -180,8 +182,8 @@ ENDDEF
DEF CONN_13X2 P 0 10 Y N 1 F N
F0 "P" 0 700 60 H V C CNN
F1 "CONN_13X2" 0 0 50 V V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -100 650 100 -650 0 1 0 N
X P1 1 -400 600 300 R 40 30 1 1 P I
@ -218,8 +220,8 @@ ENDDEF
DEF CONN_2 P 0 40 Y N 1 F N
F0 "P" -50 0 40 V V C CNN
F1 "CONN_2" 50 0 40 V V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -100 150 100 -150 0 1 0 N
X P1 1 -350 100 250 R 60 60 1 1 P I
@ -232,8 +234,8 @@ ENDDEF
DEF CONN_3X2 P 0 40 Y N 1 F N
F0 "P" 0 250 50 H V C CNN
F1 "CONN_3X2" 0 50 40 V V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -100 200 100 -100 0 1 0 N
X 1 1 -400 150 300 R 60 60 1 1 P I
@ -250,8 +252,8 @@ ENDDEF
DEF CONN_5X2 P 0 40 Y Y 1 F N
F0 "P" 0 300 60 H V C CNN
F1 "CONN_5X2" 0 0 50 V V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -100 250 100 -250 0 1 0 N
X ~ 1 -400 200 300 R 60 60 1 1 P I
@ -272,8 +274,8 @@ ENDDEF
DEF CONN_6 P 0 30 Y N 1 F N
F0 "P" -50 0 60 V V C CNN
F1 "CONN_6" 50 0 60 V V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -100 300 100 -300 0 1 0 N
X 1 1 -350 250 250 R 60 60 1 1 P I
@ -290,8 +292,8 @@ ENDDEF
DEF CONN_8X2 P 0 40 Y Y 1 F N
F0 "P" 0 450 60 H V C CNN
F1 "CONN_8X2" 0 0 50 V V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -100 400 100 -400 0 1 0 N
X ~ 1 -400 350 300 R 60 60 1 1 P I
@ -318,8 +320,8 @@ ENDDEF
DEF CRYSTAL X 0 40 N N 1 F N
F0 "X" 0 150 60 H V C CNN
F1 "CRYSTAL" 0 -150 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
P 2 0 1 16 -100 100 -100 -100 N
P 2 0 1 16 100 100 100 -100 N
@ -334,8 +336,8 @@ ENDDEF
DEF FIL-DEA U 0 40 Y Y 1 F N
F0 "U" 0 50 60 H V C CNN
F1 "FIL-DEA" 0 -50 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -300 200 300 -200 0 1 0 N
X IN 1 -600 -150 300 R 50 50 1 1 B
@ -350,8 +352,8 @@ ENDDEF
DEF FIL-LP0603 U 0 40 Y Y 1 F N
F0 "U" 0 50 60 H V C CNN
F1 "FIL-LP0603" 0 -50 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -300 200 300 -200 0 1 0 N
X OUT 1 -600 150 300 R 50 50 1 1 B
@ -364,10 +366,10 @@ ENDDEF
# FILTER
#
DEF FILTER FB 0 40 Y N 1 F N
F0 "FB" 0 150 60 H V C CNN
F1 "FILTER" 0 -100 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F0 "FB" 0 150 50 H V C CNN
F1 "FILTER" 0 -100 50 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
A -150 0 50 1 1799 0 1 0 N -100 0 -200 0
A -50 0 50 1 1799 0 1 0 N 0 0 -100 0
@ -382,14 +384,14 @@ ENDDEF
#
# GND
#
DEF ~GND #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 0 30 H I C CNN
F1 "GND" 0 -70 30 H I C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
DEF GND #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -250 50 H I C CNN
F1 "GND" 0 -150 50 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
P 4 0 1 0 -50 0 0 -50 50 0 -50 0 N
X GND 1 0 0 0 U 30 30 1 1 W N
P 6 0 1 0 0 0 0 -50 50 -50 0 -100 -50 -50 0 -50 N
X GND 1 0 0 0 D 50 50 1 1 W N
ENDDRAW
ENDDEF
#
@ -398,8 +400,8 @@ ENDDEF
DEF GSG-DIODE-TVS-BI D 0 40 N N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "GSG-DIODE-TVS-BI" 0 -100 40 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
$FPLIST
D?
SO*
@ -419,8 +421,8 @@ ENDDEF
DEF GSG-RF-CONN P 0 0 Y N 1 F N
F0 "P" 0 150 60 H V C CNN
F1 "GSG-RF-CONN" 0 -150 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
C 0 0 100 0 1 0 N
X RF 1 300 0 300 L 50 50 1 1 B
@ -433,8 +435,8 @@ ENDDEF
DEF GSG-USB-MICRO-B-SHIELDED J 0 40 Y Y 1 F N
F0 "J" 150 300 60 H V C CNN
F1 "GSG-USB-MICRO-B-SHIELDED" 400 0 60 V V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
P 4 0 1 0 350 -250 -50 -250 -50 250 350 250 N
X SHIELD 0 250 -450 200 U 50 50 1 1 P
@ -451,8 +453,8 @@ ENDDEF
DEF GSG-XC2C64A-7VQG100C U 0 40 Y Y 1 F N
F0 "U" 0 100 60 H V C CNN
F1 "GSG-XC2C64A-7VQG100C" 0 -100 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -1700 1700 1700 -1700 0 1 0 N
X BANK2F1M12 1 -2000 1200 300 R 50 50 1 1 B
@ -563,8 +565,8 @@ ENDDEF
DEF GSG-XTAL4PIN X 0 40 N N 1 F N
F0 "X" 0 150 60 H V C CNN
F1 "GSG-XTAL4PIN" 0 -150 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
P 2 0 1 16 -100 100 -100 -100 N
P 2 0 1 16 100 100 100 -100 N
@ -579,10 +581,10 @@ ENDDEF
# INDUCTOR
#
DEF INDUCTOR L 0 40 N N 1 F N
F0 "L" -50 0 40 V V C CNN
F1 "INDUCTOR" 100 0 40 V V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F0 "L" -50 0 50 V V C CNN
F1 "INDUCTOR" 100 0 50 V V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
A 0 -150 50 -889 889 0 1 0 N 1 -199 1 -100
A 0 -49 51 -889 889 0 1 0 N 1 -99 1 2
@ -598,8 +600,8 @@ ENDDEF
DEF LED D 0 40 Y N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "LED" 0 -100 50 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
$FPLIST
LED-3MM
LED-5MM
@ -610,12 +612,12 @@ $FPLIST
LEDV
$ENDFPLIST
DRAW
P 2 0 1 0 50 50 50 -50 N
P 3 0 1 0 -50 50 50 0 -50 -50 F
P 3 0 1 0 65 -40 110 -80 105 -55 N
P 3 0 1 0 80 -25 125 -65 120 -40 N
X A 1 -200 0 150 R 40 40 1 1 P
X K 2 200 0 150 L 40 40 1 1 P
P 2 0 1 0 -50 50 -50 -50 N
P 3 0 1 0 -80 -25 -125 -65 -120 -40 N
P 3 0 1 0 -65 -40 -110 -80 -105 -55 N
P 3 0 1 0 50 50 -50 0 50 -50 F
X K 1 -200 0 150 R 40 40 1 1 P
X A 2 200 0 150 L 40 40 1 1 P
ENDDRAW
ENDDEF
#
@ -624,8 +626,8 @@ ENDDEF
DEF LPC43XXFBD144 U 0 40 Y Y 1 F N
F0 "U" 0 150 60 H V C CNN
F1 "LPC43XXFBD144" 0 -150 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -2400 2400 2400 -2400 0 1 0 N
X P4_0 1 -2700 1750 300 R 50 50 1 1 B
@ -780,8 +782,8 @@ ENDDEF
DEF LXES1TBCC2-004 U 0 40 Y Y 1 F N
F0 "U" 0 250 60 H V C CNN
F1 "LXES1TBCC2-004" 0 -250 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -250 200 250 -200 0 1 0 N
X ESD1 1 -550 100 300 R 50 50 1 1 I
@ -798,8 +800,8 @@ ENDDEF
DEF MAX2837 U 0 40 Y Y 1 F N
F0 "U" 0 50 60 H V C CNN
F1 "MAX2837" 0 -50 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -1000 1000 1000 -1000 0 1 0 N
X EP 0 -1300 900 300 R 50 50 1 1 W
@ -859,8 +861,8 @@ ENDDEF
DEF MAX5864 U 0 40 Y Y 1 F N
F0 "U" 0 50 60 H V C CNN
F1 "MAX5864" 0 -50 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -900 900 900 -900 0 1 0 N
X EP 0 -1200 800 300 R 50 50 1 1 W
@ -920,8 +922,8 @@ ENDDEF
DEF MGA-81563 U 0 40 Y Y 1 F N
F0 "U" 0 50 60 H V C CNN
F1 "MGA-81563" 0 -50 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -300 300 300 -300 0 1 0 N
X GND 1 -100 -450 150 U 50 50 1 1 W
@ -938,8 +940,8 @@ ENDDEF
DEF MOS_P Q 0 40 Y N 1 F N
F0 "Q" 0 190 60 H V R CNN
F1 "MOS_P" 0 -180 60 H V R CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
ALIAS MOSFET_P
DRAW
P 2 0 1 8 -50 -100 -50 100 N
@ -960,19 +962,16 @@ ENDDEF
DEF R R 0 0 N Y 1 F N
F0 "R" 80 0 50 V V C CNN
F1 "R" 0 0 50 V V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" -70 0 30 V V C CNN
F3 "" 0 0 30 H V C CNN
$FPLIST
R?
SM0603
SM0805
R?-*
SM1206
R_*
Resistor_*
$ENDFPLIST
DRAW
S -40 150 40 -150 0 1 12 N
X ~ 1 0 250 100 D 60 60 1 1 P
X ~ 2 0 -250 100 U 60 60 1 1 P
S -40 -100 40 100 0 1 10 N
X ~ 1 0 150 50 D 60 60 1 1 P
X ~ 2 0 -150 50 U 60 60 1 1 P
ENDDRAW
ENDDEF
#
@ -981,8 +980,8 @@ ENDDEF
DEF RF-SHIELD-COVER J 0 40 Y Y 1 F N
F0 "J" 0 250 60 H V C CNN
F1 "RF-SHIELD-COVER" 0 150 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
P 4 0 1 0 -550 -100 -550 100 550 100 550 -100 N
ENDDRAW
@ -993,8 +992,8 @@ ENDDEF
DEF RF-SHIELD-FRAME J 0 40 Y Y 1 F N
F0 "J" 0 500 60 H V C CNN
F1 "RF-SHIELD-FRAME" 0 400 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
P 2 0 1 0 -450 200 -450 100 N
P 2 0 1 0 -450 350 -450 250 N
@ -1025,8 +1024,8 @@ ENDDEF
DEF RFFC5072 U 0 40 Y Y 1 F N
F0 "U" 0 100 60 H V C CNN
F1 "RFFC5072" 0 -100 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -850 850 850 -850 0 1 0 N
X EP 0 -1150 650 300 R 60 60 1 1 W
@ -1070,8 +1069,8 @@ ENDDEF
DEF SI5351C U 0 40 Y Y 1 F N
F0 "U" 0 50 60 H V C CNN
F1 "SI5351C" 0 -50 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -500 500 500 -500 0 1 0 N
X GND 0 -800 400 300 R 50 50 1 1 W
@ -1103,8 +1102,8 @@ ENDDEF
DEF SKY13317 U 0 40 Y Y 1 F N
F0 "U" 0 0 60 H V C CNN
F1 "SKY13317" 0 250 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -250 300 250 -300 0 1 0 N
X GND 0 0 -600 300 U 50 50 1 1 W
@ -1124,8 +1123,8 @@ ENDDEF
DEF SKY13350 U 0 40 Y Y 1 F N
F0 "U" 0 200 60 H V C CNN
F1 "SKY13350" 0 -200 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -300 250 300 -250 0 1 0 N
X VCTL1 1 -450 100 150 R 50 50 1 1 I
@ -1142,8 +1141,8 @@ ENDDEF
DEF SW_PUSH_SHIELDED SW 0 40 N N 1 F N
F0 "SW" 0 150 50 H V C CNN
F1 "SW_PUSH_SHIELDED" 0 -80 50 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -200 200 200 -150 0 1 0 N
S -170 50 170 60 0 1 0 N
@ -1159,8 +1158,8 @@ ENDDEF
DEF TPS62410 U 0 40 Y Y 1 F N
F0 "U" 0 -50 60 H V C CNN
F1 "TPS62410" 0 300 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -350 350 350 -350 0 1 0 N
X PP 0 0 -650 300 U 50 50 1 1 W
@ -1180,28 +1179,28 @@ ENDDEF
# VAA
#
DEF VAA #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 60 30 H I C CNN
F1 "VAA" 0 110 30 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F0 "#PWR" 0 -150 50 H I C CNN
F1 "VAA" 0 150 50 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
X VAA 1 0 0 0 U 40 40 0 0 W N
C 0 60 20 0 1 0 N
P 4 0 1 0 0 40 0 0 0 0 0 0 N
C 0 75 25 0 1 0 N
P 2 0 1 0 0 0 0 50 N
X VAA 1 0 0 0 U 50 50 1 1 W N
ENDDRAW
ENDDEF
#
# VCC
#
DEF VCC #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 100 30 H I C CNN
F1 "VCC" 0 100 30 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F0 "#PWR" 0 -150 50 H I C CNN
F1 "VCC" 0 150 50 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
X VCC 1 0 0 0 U 20 20 0 0 W N
C 0 50 20 0 1 0 N
P 3 0 1 0 0 0 0 30 0 30 N
C 0 75 25 0 1 0 N
P 2 0 1 0 0 0 0 50 N
X VCC 1 0 0 0 U 50 50 1 1 W N
ENDDRAW
ENDDEF
#
@ -1210,8 +1209,8 @@ ENDDEF
DEF W25Q80BV U 0 40 Y Y 1 F N
F0 "U" 0 -250 60 H V C CNN
F1 "W25Q80BV" 0 250 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -250 300 250 -300 0 1 0 N
X CS 1 -550 150 300 R 50 50 1 1 I

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,6 +1,6 @@
update=Wed Mar 27 00:13:41 2013
update=Wed 13 Jul 2016 05:14:22 PM MDT
version=1
last_client=eeschema
last_client=kicad
[cvpcb]
version=1
NetITyp=0
@ -46,11 +46,6 @@ LibName11=hackrf
[eeschema]
version=1
LibDir=../kicad
NetFmtName=
RptD_X=0
RptD_Y=100
RptLab=1
LabSize=60
[eeschema/libraries]
LibName1=power
LibName2=device
@ -63,23 +58,22 @@ LibName8=cmos4000
LibName9=adc-dac
LibName10=memory
LibName11=xilinx
LibName12=special
LibName13=microcontrollers
LibName14=dsp
LibName15=microchip
LibName16=analog_switches
LibName17=motorola
LibName18=texas
LibName19=intel
LibName20=audio
LibName21=interface
LibName22=digital-audio
LibName23=philips
LibName24=display
LibName25=cypress
LibName26=siliconi
LibName27=opto
LibName28=atmel
LibName29=contrib
LibName30=valves
LibName31=hackrf
LibName12=microcontrollers
LibName13=dsp
LibName14=microchip
LibName15=analog_switches
LibName16=motorola
LibName17=texas
LibName18=intel
LibName19=audio
LibName20=interface
LibName21=digital-audio
LibName22=philips
LibName23=display
LibName24=cypress
LibName25=siliconi
LibName26=opto
LibName27=atmel
LibName28=contrib
LibName29=valves
LibName30=hackrf

View File

@ -10,7 +10,6 @@ LIBS:cmos4000
LIBS:adc-dac
LIBS:memory
LIBS:xilinx
LIBS:special
LIBS:microcontrollers
LIBS:dsp
LIBS:microchip
@ -31,7 +30,7 @@ LIBS:contrib
LIBS:valves
LIBS:hackrf
LIBS:hackrf-one-cache
EELAYER 27 0
EELAYER 25 0
EELAYER END
$Descr User 17000 11000
encoding utf-8

File diff suppressed because it is too large Load Diff

47
hardware/marzipan/README Normal file
View File

@ -0,0 +1,47 @@
Copyright 2012 - 2016 Great Scott Gadgets
These files are part of HackRF.
This is a free hardware design; 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 design 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 design; see the file COPYING. If not, write to
the Free Software Foundation, Inc., 51 Franklin Street,
Boston, MA 02110-1301, USA.
Marzipan is a wideband software radio transceiver capable of running Linux.
hardware notes:
Schematic and layout files were designed in KiCad, an open source electronic
design automation package.
order of copper layers:
Copper 1: C1F (front)
Copper 2: C2
Copper 3: C3
Copper 4: C4B (back)
PCB description: 4 layer PCB 0.062 in
Copper 1 0.5 oz foil plated to approximately 0.0017 in
Dielectric 1-2 0.0119 in
Copper 2 1 oz foil (0.0014 in)
Dielectric 2-3 0.0280 in
Copper 3 1 oz foil (0.0014 in)
Dielectric 3-4 0.0119 in
Copper 4 0.5 oz foil plated to approximately 0.0017 in
FR4 or similar substrate with Er=4.5 (+/- 0.1)
double side solder mask green
single side silkscreen white
6 mil min trace width and
6 mil min isolation

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,4 @@
(fp_lib_table
(lib (name hackrf)(type Legacy)(uri ${KIPRJMOD}/../kicad/hackrf.mod)(options "")(descr ""))
(lib (name gsg-modules)(type KiCad)(uri ${KIPRJMOD}/../gsg-kicad-lib/gsg-modules.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

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,79 @@
update=Wed 13 Jul 2016 05:14:22 PM MDT
version=1
last_client=kicad
[cvpcb]
version=1
NetITyp=0
NetIExt=.net
PkgIExt=.pkg
NetDir=
LibDir=
NetType=0
[cvpcb/libraries]
EquName1=devcms
[general]
version=1
[pcbnew]
version=1
PadDrlX=320
PadDimH=600
PadDimV=600
BoardThickness=630
TxtPcbV=800
TxtPcbH=600
TxtModV=600
TxtModH=600
TxtModW=120
VEgarde=100
DrawLar=150
EdgeLar=150
TxtLar=120
MSegLar=150
LastNetListRead=marzipan.net
[pcbnew/libraries]
LibDir=../kicad
LibName1=sockets
LibName2=connect
LibName3=discret
LibName4=pin_array
LibName5=divers
LibName6=libcms
LibName7=display
LibName8=valves
LibName9=led
LibName10=dip_sockets
LibName11=hackrf
[eeschema]
version=1
LibDir=../kicad
[eeschema/libraries]
LibName1=power
LibName2=device
LibName3=transistors
LibName4=conn
LibName5=linear
LibName6=regul
LibName7=74xx
LibName8=cmos4000
LibName9=adc-dac
LibName10=memory
LibName11=xilinx
LibName12=microcontrollers
LibName13=dsp
LibName14=microchip
LibName15=analog_switches
LibName16=motorola
LibName17=texas
LibName18=intel
LibName19=audio
LibName20=interface
LibName21=digital-audio
LibName22=philips
LibName23=display
LibName24=cypress
LibName25=siliconi
LibName26=opto
LibName27=atmel
LibName28=contrib
LibName29=valves
LibName30=hackrf

View File

@ -0,0 +1,65 @@
EESchema Schematic File Version 2
LIBS:power
LIBS:device
LIBS:transistors
LIBS:conn
LIBS:linear
LIBS:regul
LIBS:74xx
LIBS:cmos4000
LIBS:adc-dac
LIBS:memory
LIBS:xilinx
LIBS:microcontrollers
LIBS:dsp
LIBS:microchip
LIBS:analog_switches
LIBS:motorola
LIBS:texas
LIBS:intel
LIBS:audio
LIBS:interface
LIBS:digital-audio
LIBS:philips
LIBS:display
LIBS:cypress
LIBS:siliconi
LIBS:opto
LIBS:atmel
LIBS:contrib
LIBS:valves
LIBS:hackrf
LIBS:marzipan-cache
EELAYER 25 0
EELAYER END
$Descr User 17000 11000
encoding utf-8
Sheet 1 4
Title "Marzipan"
Date "13 feb 2014"
Rev ""
Comp "Copyright 2012 - 2016 Great Scott Gadgets"
Comment1 "License: GPL v2"
Comment2 ""
Comment3 ""
Comment4 ""
$EndDescr
$Sheet
S 2550 3300 1050 150
U 503BB638
F0 "frontend" 60
F1 "frontend.sch" 60
$EndSheet
$Sheet
S 2550 2850 1050 150
U 50370666
F0 "baseband" 60
F1 "baseband.sch" 60
$EndSheet
$Sheet
S 2550 2400 1050 150
U 5037043E
F0 "mcu/usb/power" 60
F1 "mcu.sch" 60
$EndSheet
$EndSCHEMATC

5437
hardware/marzipan/mcu.sch Normal file

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,47 @@
Copyright 2012 - 2016 Great Scott Gadgets
These files are part of HackRF.
This is a free hardware design; 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 design 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 design; see the file COPYING. If not, write to
the Free Software Foundation, Inc., 51 Franklin Street,
Boston, MA 02110-1301, USA.
Neapolitan is an add-on for HackRF One enabling full-duplex operation.
hardware notes:
Schematic and layout files were designed in KiCad, an open source electronic
design automation package.
order of copper layers:
Copper 1: C1F (front)
Copper 2: C2
Copper 3: C3
Copper 4: C4B (back)
PCB description: 4 layer PCB 0.062 in
Copper 1 0.5 oz foil plated to approximately 0.0017 in
Dielectric 1-2 0.0119 in
Copper 2 1 oz foil (0.0014 in)
Dielectric 2-3 0.0280 in
Copper 3 1 oz foil (0.0014 in)
Dielectric 3-4 0.0119 in
Copper 4 0.5 oz foil plated to approximately 0.0017 in
FR4 or similar substrate with Er=4.5 (+/- 0.1)
double side solder mask green
single side silkscreen white
6 mil min trace width and
6 mil min isolation

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,4 @@
(fp_lib_table
(lib (name hackrf)(type Legacy)(uri ${KIPRJMOD}/../kicad/hackrf.mod)(options "")(descr ""))
(lib (name gsg-modules)(type KiCad)(uri ${KIPRJMOD}/../gsg-kicad-lib/gsg-modules.pretty)(options "")(descr ""))
)

File diff suppressed because it is too large Load Diff

2283
hardware/neapolitan/mcu.sch Normal file

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,908 @@
EESchema-LIBRARY Version 2.3
#encoding utf-8
#
# 74AHC1G14
#
DEF 74AHC1G14 U 0 30 Y Y 1 F N
F0 "U" 145 115 40 H V C CNN
F1 "74AHC1G14" 200 -100 40 H V C CNN
F2 "" 95 -135 30 H V C CNN
F3 "" 145 115 60 H V C CNN
DRAW
P 4 0 0 0 -150 150 -150 -150 150 0 -150 150 N
X GND 3 -50 -200 100 U 40 20 0 0 W
X VCC 5 -50 200 100 D 40 20 0 0 W
X ~ 2 -450 0 300 R 60 60 1 1 I
X ~ 4 450 0 300 L 60 60 1 1 O I
X ~ 2 -450 0 300 R 60 60 1 2 I I
X ~ 4 450 0 300 L 60 60 1 2 O
ENDDRAW
ENDDEF
#
# BALUN
#
DEF BALUN T 0 40 Y N 1 F N
F0 "T" 0 250 70 H V C CNN
F1 "BALUN" 0 -300 70 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
A -100 -150 50 899 1 0 1 0 N -100 -100 -50 -150
A -100 -150 50 -1 -899 0 1 0 N -50 -150 -100 -199
A -100 -50 50 899 1 0 1 0 N -100 0 -50 -50
A -100 -50 50 -1 -899 0 1 0 N -50 -50 -100 -99
A -100 50 50 899 1 0 1 0 N -100 100 -50 50
A -100 50 50 -1 -899 0 1 0 N -50 50 -100 1
A -100 150 50 899 1 0 1 0 N -100 200 -50 150
A -100 150 50 -1 -899 0 1 0 N -50 150 -100 101
A 100 -50 50 899 -1799 0 1 0 N 100 0 51 -50
A 100 -50 50 1799 -899 0 1 0 N 51 -50 100 -99
A 100 50 50 899 -1799 0 1 0 N 100 100 51 50
A 100 50 50 1799 -899 0 1 0 N 51 50 100 1
A 100 150 50 899 -1799 0 1 0 N 100 200 51 150
A 100 150 50 1799 -899 0 1 0 N 51 150 100 101
A 101 -150 50 910 -1799 0 1 0 N 101 -100 52 -150
A 101 -150 50 -912 -1799 0 1 0 N 101 -199 52 -150
P 2 0 1 0 -25 200 -25 -200 N
P 2 0 1 0 25 -200 25 200 N
X S1 1 400 -200 300 L 60 60 1 1 P
X S2 2 400 200 300 L 60 60 1 1 P
X PR1 3 -400 200 300 R 60 60 1 1 P
X PR2 4 -400 -200 300 R 60 60 1 1 P
X PM 5 -400 0 300 R 60 60 1 1 P
ENDDRAW
ENDDEF
#
# BALUN-B0310J50100AHF
#
DEF BALUN-B0310J50100AHF T 0 40 Y N 1 F N
F0 "T" 0 200 70 H V C CNN
F1 "BALUN-B0310J50100AHF" 0 -150 70 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
A -150 -50 50 1 1799 0 1 0 N -100 -50 -200 -50
A -150 100 50 -1799 -1 0 1 0 N -200 100 -100 100
A -50 -50 50 1 1799 0 1 0 N 0 -50 -100 -50
A -50 100 50 -1799 -1 0 1 0 N -100 100 0 100
A 50 -50 50 1 1799 0 1 0 N 100 -50 0 -50
A 50 100 50 -1799 -1 0 1 0 N 0 100 100 100
A 150 -50 50 1 1799 0 1 0 N 200 -50 100 -50
A 150 100 50 -1799 -1 0 1 0 N 100 100 200 100
A 150 100 50 -1799 -1 0 1 0 N 100 100 200 100
X S1 1 300 100 100 L 60 60 1 1 P
X S2 2 300 -50 100 L 60 60 1 1 P
X PR1 3 -300 100 100 R 60 60 1 1 P
X PR2 4 -300 -50 100 R 60 60 1 1 P
ENDDRAW
ENDDEF
#
# BARREL_JACK
#
DEF BARREL_JACK CON 0 40 Y Y 1 F N
F0 "CON" 0 250 60 H V C CNN
F1 "BARREL_JACK" 0 -200 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
A -300 99 49 -900 1788 0 1 0 N -300 50 -350 100
A -300 101 49 900 -1788 0 1 0 N -300 150 -350 100
S 100 150 0 50 0 1 0 N
P 2 0 1 0 -300 50 0 50 N
P 2 0 1 0 0 150 -300 150 N
P 3 0 1 0 100 0 -50 0 -50 -100 N
P 5 0 1 0 100 -100 -150 -100 -200 -50 -250 -100 -350 -100 N
X ~ 1 300 100 200 L 50 50 1 1 P
X ~ 2 300 -100 200 L 50 50 1 1 P
X ~ 3 300 0 200 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# C
#
DEF C C 0 10 N Y 1 F N
F0 "C" 25 100 50 H V L CNN
F1 "C" 25 -100 50 H V L CNN
F2 "" 38 -150 30 H V C CNN
F3 "" 0 0 60 H V C CNN
$FPLIST
C?
C_????_*
C_????
SMD*_c
Capacitor*
$ENDFPLIST
DRAW
P 2 0 1 20 -80 -30 80 -30 N
P 2 0 1 20 -80 30 80 30 N
X ~ 1 0 150 110 D 40 40 1 1 P
X ~ 2 0 -150 110 U 40 40 1 1 P
ENDDRAW
ENDDEF
#
# CONN_1
#
DEF ~CONN_1 P 0 30 N N 1 F N
F0 "P" 80 0 40 H V L CNN
F1 "CONN_1" 0 55 30 H I C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
C 0 0 31 0 1 0 N
P 2 0 1 0 -30 0 -50 0 N
X 1 1 -150 0 100 R 60 60 1 1 P
ENDDRAW
ENDDEF
#
# CONN_11X2
#
DEF CONN_11X2 P 0 10 Y N 1 F N
F0 "P" 0 600 60 H V C CNN
F1 "CONN_11X2" 0 0 50 V V C CNN
F2 "" 0 -250 60 H V C CNN
F3 "" 0 -250 60 H V C CNN
DRAW
S -100 550 100 -550 0 1 0 N
S 1200 650 1200 650 0 1 0 N
X P1 1 -400 500 300 R 60 30 1 1 P I
X P2 2 400 500 300 L 60 30 1 1 P I
X P3 3 -400 400 300 R 60 30 1 1 P I
X P4 4 400 400 300 L 60 30 1 1 P I
X P5 5 -400 300 300 R 60 30 1 1 P I
X P6 6 400 300 300 L 60 30 1 1 P I
X P7 7 -400 200 300 R 60 30 1 1 P I
X P8 8 400 200 300 L 60 30 1 1 P I
X P9 9 -400 100 300 R 60 30 1 1 P I
X P10 10 400 100 300 L 60 30 1 1 P I
X P20 20 400 -400 300 L 60 30 1 1 P I
X P11 11 -400 0 300 R 60 30 1 1 P I
X P21 21 -400 -500 300 R 60 30 1 1 P I
X P12 12 400 0 300 L 60 30 1 1 P I
X P22 22 400 -500 300 L 60 30 1 1 P I
X P13 13 -400 -100 300 R 60 30 1 1 P I
X P14 14 400 -100 300 L 60 30 1 1 P I
X P15 15 -400 -200 300 R 60 30 1 1 P I
X P16 16 400 -200 300 L 60 30 1 1 P I
X P17 17 -400 -300 300 R 60 30 1 1 P I
X P18 18 400 -300 300 L 60 30 1 1 P I
X P19 19 -400 -400 300 R 60 30 1 1 P I
ENDDRAW
ENDDEF
#
# CONN_13X2
#
DEF CONN_13X2 P 0 10 Y N 1 F N
F0 "P" 0 700 60 H V C CNN
F1 "CONN_13X2" 0 0 50 V V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -100 650 100 -650 0 1 0 N
X P1 1 -400 600 300 R 40 30 1 1 P I
X P2 2 400 600 300 L 40 30 1 1 P I
X P3 3 -400 500 300 R 40 30 1 1 P I
X P4 4 400 500 300 L 40 30 1 1 P I
X P5 5 -400 400 300 R 40 30 1 1 P I
X P6 6 400 400 300 L 40 30 1 1 P I
X P7 7 -400 300 300 R 40 30 1 1 P I
X P8 8 400 300 300 L 40 30 1 1 P I
X P9 9 -400 200 300 R 40 30 1 1 P I
X P10 10 400 200 300 L 40 30 1 1 P I
X P20 20 400 -300 300 L 40 30 1 1 P I
X P11 11 -400 100 300 R 40 30 1 1 P I
X P21 21 -400 -400 300 R 40 30 1 1 P I
X P12 12 400 100 300 L 40 30 1 1 P I
X P22 22 400 -400 300 L 40 30 1 1 P I
X P13 13 -400 0 300 R 40 30 1 1 P I
X P23 23 -400 -500 300 R 40 30 1 1 P I
X P14 14 400 0 300 L 40 30 1 1 P I
X P20 24 400 -500 300 L 40 30 1 1 P I
X P15 15 -400 -100 300 R 40 30 1 1 P I
X P24 25 -400 -600 300 R 40 30 1 1 P I
X P16 16 400 -100 300 L 40 30 1 1 P I
X P22 26 400 -600 300 L 40 30 1 1 P I
X P17 17 -400 -200 300 R 40 30 1 1 P I
X P18 18 400 -200 300 L 40 30 1 1 P I
X P19 19 -400 -300 300 R 40 30 1 1 P I
ENDDRAW
ENDDEF
#
# CONN_2
#
DEF CONN_2 P 0 40 Y N 1 F N
F0 "P" -50 0 40 V V C CNN
F1 "CONN_2" 50 0 40 V V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -100 150 100 -150 0 1 0 N
X P1 1 -350 100 250 R 60 60 1 1 P I
X PM 2 -350 -100 250 R 60 60 1 1 P I
ENDDRAW
ENDDEF
#
# CONN_3X2
#
DEF CONN_3X2 P 0 40 Y N 1 F N
F0 "P" 0 250 50 H V C CNN
F1 "CONN_3X2" 0 50 40 V V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -100 200 100 -100 0 1 0 N
X 1 1 -400 150 300 R 60 60 1 1 P I
X 2 2 400 150 300 L 60 60 1 1 P I
X 3 3 -400 50 300 R 60 60 1 1 P I
X 4 4 400 50 300 L 60 60 1 1 P I
X 5 5 -400 -50 300 R 60 60 1 1 P I
X 6 6 400 -50 300 L 60 60 1 1 P I
ENDDRAW
ENDDEF
#
# CONN_8X2
#
DEF CONN_8X2 P 0 40 Y Y 1 F N
F0 "P" 0 450 60 H V C CNN
F1 "CONN_8X2" 0 0 50 V V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -100 400 100 -400 0 1 0 N
X ~ 1 -400 350 300 R 60 60 1 1 P I
X ~ 2 400 350 300 L 60 60 1 1 P I
X ~ 3 -400 250 300 R 60 60 1 1 P I
X ~ 4 400 250 300 L 60 60 1 1 P I
X ~ 5 -400 150 300 R 60 60 1 1 P I
X ~ 6 400 150 300 L 60 60 1 1 P I
X ~ 7 -400 50 300 R 60 60 1 1 P I
X ~ 8 400 50 300 L 60 60 1 1 P I
X ~ 9 -400 -50 300 R 60 60 1 1 P I
X ~ 10 400 -50 300 L 60 60 1 1 P I
X ~ 11 -400 -150 300 R 60 60 1 1 P I
X ~ 12 400 -150 300 L 60 60 1 1 P I
X ~ 13 -400 -250 300 R 60 60 1 1 P I
X ~ 14 400 -250 300 L 60 60 1 1 P I
X ~ 15 -400 -350 300 R 60 60 1 1 P I
X ~ 16 400 -350 300 L 60 60 1 1 P I
ENDDRAW
ENDDEF
#
# D_Schottky
#
DEF D_Schottky D 0 40 N N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "D_Schottky" 0 -100 50 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
$FPLIST
D-Pak_TO252AA
Diode_*
*SingleDiode
*SingleDiode*
*_Diode_*
$ENDFPLIST
DRAW
P 3 0 1 0 50 50 -50 0 50 -50 F
P 6 0 1 8 -75 25 -75 50 -50 50 -50 -50 -25 -50 -25 -25 N
X K 1 -150 0 100 R 50 50 1 1 P
X A 2 150 0 100 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# FIL-DEA
#
DEF FIL-DEA U 0 40 Y Y 1 F N
F0 "U" 0 50 60 H V C CNN
F1 "FIL-DEA" 0 -50 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -300 200 300 -200 0 1 0 N
X IN 1 -600 -150 300 R 50 50 1 1 B
X GND 2 600 -150 300 L 50 50 1 1 W
X OUT 3 600 150 300 L 50 50 1 1 B
X GND 4 -600 150 300 R 50 50 1 1 W
ENDDRAW
ENDDEF
#
# FIL-LP0603
#
DEF FIL-LP0603 U 0 40 Y Y 1 F N
F0 "U" 0 50 60 H V C CNN
F1 "FIL-LP0603" 0 -50 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -300 200 300 -200 0 1 0 N
X OUT 1 -600 150 300 R 50 50 1 1 B
X GND 2 -600 -150 300 R 50 50 1 1 W
X GND 3 600 -150 300 L 50 50 1 1 W
X IN 4 600 150 300 L 50 50 1 1 B
ENDDRAW
ENDDEF
#
# FILTER
#
DEF FILTER FB 0 40 Y N 1 F N
F0 "FB" 0 150 50 H V C CNN
F1 "FILTER" 0 -100 50 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
A -150 0 50 1 1799 0 1 0 N -100 0 -200 0
A -50 0 50 1 1799 0 1 0 N 0 0 -100 0
A 0 0 0 0 0 0 1 0 N 0 0 0 0
A 50 0 50 1 1799 0 1 0 N 100 0 0 0
A 150 0 50 1 1799 0 1 0 N 200 0 100 0
S -225 75 225 -50 0 1 0 N
X 1 1 -350 0 150 R 40 40 1 1 P
X 2 2 350 0 150 L 40 40 1 1 P
ENDDRAW
ENDDEF
#
# FOX924B
#
DEF FOX924B X 0 40 Y Y 1 F N
F0 "X" 0 150 60 H V C CNN
F1 "FOX924B" 0 -150 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -250 100 250 -100 0 1 0 N
X NC 1 -400 -50 150 R 50 50 1 1 N
X GND 2 400 -50 150 L 50 50 1 1 W
X OUT 3 400 50 150 L 50 50 1 1 O
X VCC 4 -400 50 150 R 50 50 1 1 W
ENDDRAW
ENDDEF
#
# GND
#
DEF GND #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -250 50 H I C CNN
F1 "GND" 0 -150 50 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
P 6 0 1 0 0 0 0 -50 50 -50 0 -100 -50 -50 0 -50 N
X GND 1 0 0 0 D 50 50 1 1 W N
ENDDRAW
ENDDEF
#
# GSG-DIODE-TVS-BI
#
DEF GSG-DIODE-TVS-BI D 0 40 N N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "GSG-DIODE-TVS-BI" 0 -100 40 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
$FPLIST
D?
SO*
SM*
$ENDFPLIST
DRAW
P 5 0 1 8 -20 50 0 30 0 -30 20 -50 20 -50 N
P 5 0 1 0 0 0 -100 50 -100 -50 0 0 0 0 F
P 5 0 1 0 0 0 100 50 100 -50 0 0 0 0 F
X A 1 -250 0 150 R 40 40 1 1 P
X K 2 250 0 150 L 40 40 1 1 P
ENDDRAW
ENDDEF
#
# GSG-RF-CONN
#
DEF GSG-RF-CONN P 0 0 Y N 1 F N
F0 "P" 0 150 60 H V C CNN
F1 "GSG-RF-CONN" 0 -150 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
C 0 0 100 0 1 0 N
X RF 1 300 0 300 L 50 50 1 1 B
X GND 2 0 -400 300 U 50 50 1 1 W
ENDDRAW
ENDDEF
#
# GSG-USB-MICRO-B-SHIELDED
#
DEF GSG-USB-MICRO-B-SHIELDED J 0 40 Y Y 1 F N
F0 "J" 150 300 60 H V C CNN
F1 "GSG-USB-MICRO-B-SHIELDED" 400 0 60 V V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
P 4 0 1 0 350 -250 -50 -250 -50 250 350 250 N
X SHIELD 0 250 -450 200 U 50 50 1 1 P
X VBUS 1 -250 200 200 R 50 50 1 1 w
X D- 2 -250 100 200 R 50 50 1 1 B
X D+ 3 -250 0 200 R 50 50 1 1 B
X ID 4 -250 -100 200 R 50 50 1 1 I
X GND 5 -250 -200 200 R 50 50 1 1 w
ENDDRAW
ENDDEF
#
# GSG-XTAL4PIN
#
DEF GSG-XTAL4PIN X 0 40 N N 1 F N
F0 "X" 0 150 60 H V C CNN
F1 "GSG-XTAL4PIN" 0 -150 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
P 2 0 1 16 -100 100 -100 -100 N
P 2 0 1 16 100 100 100 -100 N
P 5 0 1 12 -50 50 50 50 50 -50 -50 -50 -50 50 f
X 1 1 -300 0 200 R 40 40 1 1 P
X 2 2 -100 -300 200 U 40 40 1 1 P
X 3 3 300 0 200 L 40 40 1 1 P
X 4 4 100 -300 200 U 40 40 1 1 P
ENDDRAW
ENDDEF
#
# INDUCTOR
#
DEF INDUCTOR L 0 40 N N 1 F N
F0 "L" -50 0 50 V V C CNN
F1 "INDUCTOR" 100 0 50 V V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
A 0 -150 50 -889 889 0 1 0 N 1 -199 1 -100
A 0 -49 51 -889 889 0 1 0 N 1 -99 1 2
A 0 51 51 -889 889 0 1 0 N 1 1 1 102
A 0 148 48 -889 889 0 1 0 N 1 101 1 196
X 1 1 0 300 100 D 70 70 1 1 P
X 2 2 0 -300 100 U 70 70 1 1 P
ENDDRAW
ENDDEF
#
# KT2520
#
DEF KT2520 X 0 40 Y Y 1 F N
F0 "X" 0 200 60 H V C CNN
F1 "KT2520" 0 -200 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -250 150 250 -150 0 1 0 N
X GND 1 -400 100 150 R 50 50 1 1 W
X NC 2 -400 0 150 R 50 50 1 1 N
X GND 3 -400 -100 150 R 50 50 1 1 W
X OUT 4 400 -100 150 L 50 50 1 1 O
X NC 5 400 0 150 L 50 50 1 1 N
X VCC 6 400 100 150 L 50 50 1 1 W
ENDDRAW
ENDDEF
#
# LED
#
DEF LED D 0 40 Y N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "LED" 0 -100 50 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
$FPLIST
LED-3MM
LED-5MM
LED-10MM
LED-0603
LED-0805
LED-1206
LEDV
$ENDFPLIST
DRAW
P 2 0 1 0 -50 50 -50 -50 N
P 3 0 1 0 -80 -25 -125 -65 -120 -40 N
P 3 0 1 0 -65 -40 -110 -80 -105 -55 N
P 3 0 1 0 50 50 -50 0 50 -50 F
X K 1 -200 0 150 R 40 40 1 1 P
X A 2 200 0 150 L 40 40 1 1 P
ENDDRAW
ENDDEF
#
# MAX2837
#
DEF MAX2837 U 0 40 Y Y 1 F N
F0 "U" 0 50 60 H V C CNN
F1 "MAX2837" 0 -50 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -1000 1000 1000 -1000 0 1 0 N
X EP 0 -1300 900 300 R 50 50 1 1 W
X VCCRXLNA 1 -1300 550 300 R 50 50 1 1 W
X GNDRXLNA 2 -1300 450 300 R 50 50 1 1 W
X B5 3 -1300 350 300 R 50 50 1 1 I
X RXRF+ 4 -1300 250 300 R 50 50 1 1 I
X RXRF- 5 -1300 150 300 R 50 50 1 1 I
X B4 6 -1300 50 300 R 50 50 1 1 I
X VCCTXPAD 7 -1300 -50 300 R 50 50 1 1 W
X B3 8 -1300 -150 300 R 50 50 1 1 I
X B2 9 -1300 -250 300 R 50 50 1 1 I
X TXRF+ 10 -1300 -350 300 R 50 50 1 1 O
X VCCDIG 20 150 -1300 300 U 50 50 1 1 W
X CS 30 1300 -50 300 L 50 50 1 1 I
X RXHP 40 250 1300 300 D 50 50 1 1 I
X TXRF- 11 -1300 -450 300 R 50 50 1 1 O
X VCCCP 21 250 -1300 300 U 50 50 1 1 W
X DIN 31 1300 50 300 L 50 50 1 1 I
X VCCRXFL 41 150 1300 300 D 50 50 1 1 W
X B1 12 -1300 -550 300 R 50 50 1 1 I
X GNDCP 22 350 -1300 300 U 50 50 1 1 W
X RSSI 32 1300 150 300 L 50 50 1 1 O
X TXBBI- 42 50 1300 300 D 50 50 1 1 I
X VCCTXMX 13 -550 -1300 300 U 50 50 1 1 W
X CPOUT+ 23 450 -1300 300 U 50 50 1 1 O
X B7 33 1300 250 300 L 50 50 1 1 I
X TXBBI+ 43 -50 1300 300 D 50 50 1 1 I
X PABIAS 14 -450 -1300 300 U 50 50 1 1 O
X CPOUT- 24 550 -1300 300 U 50 50 1 1 O
X B6 34 1300 350 300 L 50 50 1 1 I
X TXBBQ+ 44 -150 1300 300 D 50 50 1 1 I
X SCLK 15 -350 -1300 300 U 50 50 1 1 I
X ENABLE 25 1300 -550 300 L 50 50 1 1 I
X RXBBQ- 35 1300 450 300 L 50 50 1 1 O
X TXBBQ- 45 -250 1300 300 D 50 50 1 1 I
X CLOCKOUT 16 -250 -1300 300 U 50 50 1 1 O
X GNDVCO 26 1300 -450 300 L 50 50 1 1 W
X RXBBQ+ 36 1300 550 300 L 50 50 1 1 O
X VCCRXMX 46 -350 1300 300 D 50 50 1 1 W
X XTAL2 17 -150 -1300 300 U 50 50 1 1 I
X BYPASS 27 1300 -350 300 L 50 50 1 1 O
X RXBBI- 37 550 1300 300 D 50 50 1 1 O
X TXENABLE 47 -450 1300 300 D 50 50 1 1 I
X XTAL1 18 -50 -1300 300 U 50 50 1 1 O
X VCCVCO 28 1300 -250 300 L 50 50 1 1 W
X RXBBI+ 38 450 1300 300 D 50 50 1 1 O
X RXENABLE 48 -550 1300 300 D 50 50 1 1 I
X VCCXTAL 19 50 -1300 300 U 50 50 1 1 W
X DOUT 29 1300 -150 300 L 50 50 1 1 O
X VCCRXVGA 39 350 1300 300 D 50 50 1 1 W
ENDDRAW
ENDDEF
#
# MGA-81563
#
DEF MGA-81563 U 0 40 Y Y 1 F N
F0 "U" 0 50 60 H V C CNN
F1 "MGA-81563" 0 -50 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -300 300 300 -300 0 1 0 N
X GND 1 -100 -450 150 U 50 50 1 1 W
X GND 2 0 -450 150 U 50 50 1 1 W
X IN 3 100 -450 150 U 50 50 1 1 I
X GND 4 100 450 150 D 50 50 1 1 W
X GND 5 0 450 150 D 50 50 1 1 W
X OUT 6 -100 450 150 D 50 50 1 1 O
ENDDRAW
ENDDEF
#
# MOS_P
#
DEF MOS_P Q 0 40 Y N 1 F N
F0 "Q" 0 190 60 H V R CNN
F1 "MOS_P" 0 -180 60 H V R CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
ALIAS MOSFET_P
DRAW
P 2 0 1 8 -50 -100 -50 100 N
P 2 0 1 10 0 -150 0 150 N
P 2 0 1 8 30 0 0 0 N
P 2 0 1 0 100 -100 0 -100 N
P 2 0 1 0 100 100 0 100 N
P 3 0 1 0 80 0 100 0 100 -100 N
P 5 0 1 8 30 40 30 -30 80 0 30 40 30 40 N
X D D 100 200 100 D 40 40 1 1 P
X G G -200 0 150 R 40 40 1 1 I
X S S 100 -200 100 U 40 40 1 1 P
ENDDRAW
ENDDEF
#
# NX5P2553GV
#
DEF NX5P2553GV U 0 40 Y Y 1 F N
F0 "U" 0 250 60 H V C CNN
F1 "NX5P2553GV" 0 -250 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -250 200 250 -200 0 1 0 N
X VIN 1 -400 100 150 R 50 50 1 1 W
X GND 2 -400 0 150 R 50 50 1 1 W
X EN 3 -400 -100 150 R 50 50 1 1 I
X FAULT 4 400 -100 150 L 50 50 1 1 O
X ILIM 5 400 0 150 L 50 50 1 1 I
X VOUT 6 400 100 150 L 50 50 1 1 w
ENDDRAW
ENDDEF
#
# OH4
#
DEF OH4 X 0 40 Y Y 1 F N
F0 "X" 0 150 60 H V C CNN
F1 "OH4" 0 -150 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -300 100 300 -100 0 1 0 N
X NC/VC 1 -500 50 200 R 50 50 1 1 I
X GND 7 -500 -50 200 R 50 50 1 1 W
X OUT 8 500 -50 200 L 50 50 1 1 O
X VCC 14 500 50 200 L 50 50 1 1 W
ENDDRAW
ENDDEF
#
# R
#
DEF R R 0 0 N Y 1 F N
F0 "R" 80 0 50 V V C CNN
F1 "R" 0 0 50 V V C CNN
F2 "" -70 0 30 V V C CNN
F3 "" 0 0 30 H V C CNN
$FPLIST
R_*
Resistor_*
$ENDFPLIST
DRAW
S -40 -100 40 100 0 1 10 N
X ~ 1 0 150 50 D 60 60 1 1 P
X ~ 2 0 -150 50 U 60 60 1 1 P
ENDDRAW
ENDDEF
#
# RF-SHIELD-COVER
#
DEF RF-SHIELD-COVER J 0 40 Y Y 1 F N
F0 "J" 0 250 60 H V C CNN
F1 "RF-SHIELD-COVER" 0 150 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
P 4 0 1 0 -550 -100 -550 100 550 100 550 -100 N
ENDDRAW
ENDDEF
#
# RF-SHIELD-FRAME
#
DEF RF-SHIELD-FRAME J 0 40 Y Y 1 F N
F0 "J" 0 500 60 H V C CNN
F1 "RF-SHIELD-FRAME" 0 400 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
P 2 0 1 0 -450 200 -450 100 N
P 2 0 1 0 -450 350 -450 250 N
P 2 0 1 0 -450 500 -450 400 N
P 2 0 1 0 -350 0 -250 0 N
P 2 0 1 0 -250 600 -350 600 N
P 2 0 1 0 -200 0 -100 0 N
P 2 0 1 0 -100 600 -200 600 N
P 2 0 1 0 -50 0 50 0 N
P 2 0 1 0 50 600 -50 600 N
P 2 0 1 0 100 0 200 0 N
P 2 0 1 0 200 600 100 600 N
P 2 0 1 0 250 0 350 0 N
P 2 0 1 0 350 600 250 600 N
P 2 0 1 0 450 100 450 200 N
P 2 0 1 0 450 250 450 350 N
P 2 0 1 0 450 400 450 500 N
P 3 0 1 0 -450 50 -450 0 -400 0 N
P 3 0 1 0 -400 600 -450 600 -450 550 N
P 3 0 1 0 400 0 450 0 450 50 N
P 3 0 1 0 450 550 450 600 400 600 N
X SHIELD 0 0 -300 300 U 50 50 1 1 P
ENDDRAW
ENDDEF
#
# RFFC5072
#
DEF RFFC5072 U 0 40 Y Y 1 F N
F0 "U" 0 100 60 H V C CNN
F1 "RFFC5072" 0 -100 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -850 850 850 -850 0 1 0 N
X EP 0 -1150 650 300 R 60 60 1 1 W
X ENBL/GPO5 1 -1150 350 300 R 50 50 1 1 B
X EXT_LO 2 -1150 250 300 R 50 50 1 1 I
X EXT_LO_DEC 3 -1150 150 300 R 50 50 1 1 P
X REXT 4 -1150 50 300 R 50 50 1 1 P
X ANA_VDD1 5 -1150 -50 300 R 50 50 1 1 W
X LFILT1 6 -1150 -150 300 R 50 50 1 1 O
X LFITLT2 7 -1150 -250 300 R 50 50 1 1 O
X LFILT3 8 -1150 -350 300 R 50 50 1 1 I
X MODE/GPO6 9 -350 -1150 300 U 50 50 1 1 B
X REF_IN 10 -250 -1150 300 U 50 50 1 1 I
X NC 20 1150 -50 300 L 50 50 1 1 N
X ENX 30 -150 1150 300 D 50 50 1 1 I
X NC 11 -150 -1150 300 U 50 50 1 1 N
X NC 21 1150 50 300 L 50 50 1 1 N
X SCLK 31 -250 1150 300 D 50 50 1 1 I
X TM 12 -50 -1150 300 U 50 50 1 1 W
X ANA_VDD2 22 1150 150 300 L 50 50 1 1 W
X SDATA 32 -350 1150 300 D 50 50 1 1 I
X NC 13 50 -1150 300 U 50 50 1 1 N
X MIX_IPP 23 1150 250 300 L 50 50 1 1 I
X NC 14 150 -1150 300 U 50 50 1 1 N
X MIX_IPN 24 1150 350 300 L 50 50 1 1 I
X GPO1/ADD1 15 250 -1150 300 U 50 50 1 1 B
X GPO3/FM 25 350 1150 300 D 50 50 1 1 B
X GPO2/ADD2 16 350 -1150 300 U 50 50 1 1 B
X GPO4/LD/DO 26 250 1150 300 D 50 50 1 1 B
X NC 17 1150 -350 300 L 50 50 1 1 N
X MIX_OPN 27 150 1150 300 D 50 50 1 1 O
X NC 18 1150 -250 300 L 50 50 1 1 N
X MIX_OPP 28 50 1150 300 D 50 50 1 1 O
X DIG_VDD 19 1150 -150 300 L 50 50 1 1 W
X RESETX 29 -50 1150 300 D 50 50 1 1 I
ENDDRAW
ENDDEF
#
# SI5351C
#
DEF SI5351C U 0 40 Y Y 1 F N
F0 "U" 0 50 60 H V C CNN
F1 "SI5351C" 0 -50 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -500 500 500 -500 0 1 0 N
X GND 0 -800 400 300 R 50 50 1 1 W
X XA 1 -800 200 300 R 50 50 1 1 I
X XB 2 -800 100 300 R 50 50 1 1 I
X INTR 3 -800 0 300 R 50 50 1 1 O
X SCL 4 -800 -100 300 R 50 50 1 1 I
X SDA 5 -800 -200 300 R 50 50 1 1 B
X CLKIN 6 -200 -800 300 U 50 50 1 1 I
X OEB 7 -100 -800 300 U 50 50 1 1 I
X CLK3 8 0 -800 300 U 50 50 1 1 O
X CLK2 9 100 -800 300 U 50 50 1 1 O
X VDDOB 10 200 -800 300 U 50 50 1 1 W
X VDD 20 -200 800 300 D 50 50 1 1 W
X VDDOA 11 800 -200 300 L 50 50 1 1 W
X CLK1 12 800 -100 300 L 50 50 1 1 O
X CLK0 13 800 0 300 L 50 50 1 1 O
X VDDOD 14 800 100 300 L 50 50 1 1 W
X CLK7 15 800 200 300 L 50 50 1 1 O
X CLK6 16 200 800 300 D 50 50 1 1 O
X CLK5 17 100 800 300 D 50 50 1 1 O
X VDDOC 18 0 800 300 D 50 50 1 1 W
X CLK4 19 -100 800 300 D 50 50 1 1 O
ENDDRAW
ENDDEF
#
# SKY13317
#
DEF SKY13317 U 0 40 Y Y 1 F N
F0 "U" 0 0 60 H V C CNN
F1 "SKY13317" 0 250 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -250 300 250 -300 0 1 0 N
X GND 0 0 -600 300 U 50 50 1 1 W
X RFC 1 -550 150 300 R 50 50 1 1 B
X NC 2 -550 50 300 R 50 50 1 1 N
X V1 3 -550 -50 300 R 50 50 1 1 I
X RF1 4 -550 -150 300 R 50 50 1 1 B
X RF2 5 550 -150 300 L 50 50 1 1 B
X V2 6 550 -50 300 L 50 50 1 1 I
X V3 7 550 50 300 L 50 50 1 1 I
X RF3 8 550 150 300 L 50 50 1 1 B
ENDDRAW
ENDDEF
#
# SKY13350
#
DEF SKY13350 U 0 40 Y Y 1 F N
F0 "U" 0 200 60 H V C CNN
F1 "SKY13350" 0 -200 60 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
S -300 250 300 -250 0 1 0 N
X VCTL1 1 -450 100 150 R 50 50 1 1 I
X OUT1 2 -450 0 150 R 50 50 1 1 B
X GND 3 -450 -100 150 R 50 50 1 1 W
X OUT2 4 450 -100 150 L 50 50 1 1 B
X VCTL2 5 450 0 150 L 50 50 1 1 I
X INPUT 6 450 100 150 L 50 50 1 1 B
ENDDRAW
ENDDEF
#
# TCA6424A
#
DEF TCA6424A U 0 40 Y Y 1 F N
F0 "U" 0 50 60 H V C CNN
F1 "TCA6424A" 0 -50 60 H V C CNN
F2 "" 0 0 40 H V C CNN
F3 "" 0 0 40 H V C CNN
DRAW
S -600 600 600 -600 0 1 0 N
X GND 0 -750 550 150 R 50 50 1 1 W
X P00 1 -750 350 150 R 50 50 1 1 B
X P01 2 -750 250 150 R 50 50 1 1 B
X P02 3 -750 150 150 R 50 50 1 1 B
X P03 4 -750 50 150 R 50 50 1 1 B
X P04 5 -750 -50 150 R 50 50 1 1 B
X P05 6 -750 -150 150 R 50 50 1 1 B
X P06 7 -750 -250 150 R 50 50 1 1 B
X P07 8 -750 -350 150 R 50 50 1 1 B
X P10 9 -350 -750 150 U 50 50 1 1 B
X P11 10 -250 -750 150 U 50 50 1 1 B
X P23 20 750 -50 150 L 50 50 1 1 B
X SDA 30 -150 750 150 D 50 50 1 1 B
X P12 11 -150 -750 150 U 50 50 1 1 B
X P24 21 750 50 150 L 50 50 1 1 B
X VCCI 31 -250 750 150 D 50 50 1 1 W
X P13 12 -50 -750 150 U 50 50 1 1 B
X P25 22 750 150 150 L 50 50 1 1 B
X !INT 32 -350 750 150 D 50 50 1 1 O
X P14 13 50 -750 150 U 50 50 1 1 B
X P26 23 750 250 150 L 50 50 1 1 B
X P15 14 150 -750 150 U 50 50 1 1 B
X P27 24 750 350 150 L 50 50 1 1 B
X P16 15 250 -750 150 U 50 50 1 1 B
X GND 25 350 750 150 D 50 50 1 1 W
X P17 16 350 -750 150 U 50 50 1 1 B
X ADDR 26 250 750 150 D 50 50 1 1 I
X P20 17 750 -350 150 L 50 50 1 1 B
X VCCP 27 150 750 150 D 50 50 1 1 W
X P21 18 750 -250 150 L 50 50 1 1 B
X !RESET 28 50 750 150 D 50 50 1 1 I
X P22 19 750 -150 150 L 50 50 1 1 B
X SCL 29 -50 750 150 D 50 50 1 1 B
ENDDRAW
ENDDEF
#
# TCR2EF
#
DEF TCR2EF U 0 40 Y Y 1 F N
F0 "U" 0 200 40 H V C CNN
F1 "TCR2EF" 0 -200 40 H V C CNN
F2 "" 0 0 40 H V C CNN
F3 "" 0 0 40 H V C CNN
DRAW
S -250 150 250 -150 0 1 0 N
X VIN 1 -400 100 150 R 50 50 1 1 W
X GND 2 -400 0 150 R 50 50 1 1 W
X CTRL 3 -400 -100 150 R 50 50 1 1 I
X NC 4 400 -100 150 L 50 50 1 1 N
X VOUT 5 400 100 150 L 50 50 1 1 w
ENDDRAW
ENDDEF
#
# VAA
#
DEF VAA #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -150 50 H I C CNN
F1 "VAA" 0 150 50 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
C 0 75 25 0 1 0 N
P 2 0 1 0 0 0 0 50 N
X VAA 1 0 0 0 U 50 50 1 1 W N
ENDDRAW
ENDDEF
#
# VCC
#
DEF VCC #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -150 50 H I C CNN
F1 "VCC" 0 150 50 H V C CNN
F2 "" 0 0 60 H V C CNN
F3 "" 0 0 60 H V C CNN
DRAW
C 0 75 25 0 1 0 N
P 2 0 1 0 0 0 0 50 N
X VCC 1 0 0 0 U 50 50 1 1 W N
ENDDRAW
ENDDEF
#
#End Library

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

@ -0,0 +1,80 @@
update=Fri 02 Sep 2016 06:05:25 PM MDT
version=1
last_client=kicad
[cvpcb]
version=1
NetITyp=0
NetIExt=.net
PkgIExt=.pkg
NetDir=
LibDir=
NetType=0
[cvpcb/libraries]
EquName1=devcms
[general]
version=1
[pcbnew]
version=1
PadDrlX=320
PadDimH=600
PadDimV=600
BoardThickness=630
TxtPcbV=800
TxtPcbH=600
TxtModV=600
TxtModH=600
TxtModW=120
VEgarde=100
DrawLar=150
EdgeLar=150
TxtLar=120
MSegLar=150
LastNetListRead=neapolitan.net
[pcbnew/libraries]
LibDir=../kicad
LibName1=sockets
LibName2=connect
LibName3=discret
LibName4=pin_array
LibName5=divers
LibName6=libcms
LibName7=display
LibName8=valves
LibName9=led
LibName10=dip_sockets
LibName11=hackrf
[eeschema]
version=1
LibDir=../kicad;../gsg-kicad-lib
[eeschema/libraries]
LibName1=power
LibName2=device
LibName3=transistors
LibName4=conn
LibName5=linear
LibName6=regul
LibName7=74xx
LibName8=cmos4000
LibName9=adc-dac
LibName10=memory
LibName11=xilinx
LibName12=microcontrollers
LibName13=dsp
LibName14=microchip
LibName15=analog_switches
LibName16=motorola
LibName17=texas
LibName18=intel
LibName19=audio
LibName20=interface
LibName21=digital-audio
LibName22=philips
LibName23=display
LibName24=cypress
LibName25=siliconi
LibName26=opto
LibName27=atmel
LibName28=contrib
LibName29=valves
LibName30=hackrf
LibName31=gsg-symbols

View File

@ -0,0 +1,66 @@
EESchema Schematic File Version 2
LIBS:power
LIBS:device
LIBS:transistors
LIBS:conn
LIBS:linear
LIBS:regul
LIBS:74xx
LIBS:cmos4000
LIBS:adc-dac
LIBS:memory
LIBS:xilinx
LIBS:microcontrollers
LIBS:dsp
LIBS:microchip
LIBS:analog_switches
LIBS:motorola
LIBS:texas
LIBS:intel
LIBS:audio
LIBS:interface
LIBS:digital-audio
LIBS:philips
LIBS:display
LIBS:cypress
LIBS:siliconi
LIBS:opto
LIBS:atmel
LIBS:contrib
LIBS:valves
LIBS:hackrf
LIBS:gsg-symbols
LIBS:neapolitan-cache
EELAYER 25 0
EELAYER END
$Descr User 17000 11000
encoding utf-8
Sheet 1 4
Title "Neapolitan"
Date "13 feb 2014"
Rev ""
Comp "Copyright 2012 - 2016 Great Scott Gadgets"
Comment1 "License: GPL v2"
Comment2 ""
Comment3 ""
Comment4 ""
$EndDescr
$Sheet
S 2550 3300 1050 150
U 503BB638
F0 "frontend" 60
F1 "frontend.sch" 60
$EndSheet
$Sheet
S 2550 2850 1050 150
U 50370666
F0 "baseband" 60
F1 "baseband.sch" 60
$EndSheet
$Sheet
S 2550 2400 1050 150
U 5037043E
F0 "mcu/usb/power" 60
F1 "mcu.sch" 60
$EndSheet
$EndSCHEMATC

View File

@ -5,7 +5,7 @@ produce a low cost, open source software radio platform.
###Prerequisites for Linux (Debian/Ubuntu):
`sudo apt-get install build-essential cmake libusb-1.0-0-dev pkg-config`
`sudo apt-get install build-essential cmake libusb-1.0-0-dev pkg-config libfftw3-dev`
###Build host software on Linux:

View File

@ -0,0 +1,22 @@
# - Find FFTW
# Find the native FFTW includes and library
#
# FFTW_INCLUDES - where to find fftw3.h
# FFTW_LIBRARIES - List of libraries when using FFTW.
# FFTW_FOUND - True if FFTW found.
if (FFTW_INCLUDES)
# Already in cache, be silent
set (FFTW_FIND_QUIETLY TRUE)
endif (FFTW_INCLUDES)
find_path (FFTW_INCLUDES fftw3.h)
find_library (FFTW_LIBRARIES NAMES fftw3)
# handle the QUIETLY and REQUIRED arguments and set FFTW_FOUND to TRUE if
# all listed variables are TRUE
include (FindPackageHandleStandardArgs)
find_package_handle_standard_args (FFTW DEFAULT_MSG FFTW_LIBRARIES FFTW_INCLUDES)
mark_as_advanced (FFTW_LIBRARIES FFTW_INCLUDES)

View File

@ -24,7 +24,7 @@
cmake_minimum_required(VERSION 2.8)
project(hackrf-tools C)
set(MAJOR_VERSION 0)
set(MINOR_VERSION 4)
set(MINOR_VERSION 5)
set(PACKAGE hackrf-tools)
set(VERSION_STRING ${MAJOR_VERSION}.${MINOR_VERSION})
set(VERSION ${VERSION_STRING})

View File

@ -23,49 +23,42 @@
set(INSTALL_DEFAULT_BINDIR "bin" CACHE STRING "Appended to CMAKE_INSTALL_PREFIX")
INCLUDE(FindPkgConfig)
pkg_check_modules(FFTW REQUIRED fftw3f)
if(MSVC)
add_library(libgetopt_static STATIC
../getopt/getopt.c
)
add_library(libgetopt_static STATIC
../getopt/getopt.c
)
endif()
add_executable(hackrf_max2837 hackrf_max2837.c)
install(TARGETS hackrf_max2837 RUNTIME DESTINATION ${INSTALL_DEFAULT_BINDIR})
add_executable(hackrf_si5351c hackrf_si5351c.c)
install(TARGETS hackrf_si5351c RUNTIME DESTINATION ${INSTALL_DEFAULT_BINDIR})
add_executable(hackrf_transfer hackrf_transfer.c)
install(TARGETS hackrf_transfer RUNTIME DESTINATION ${INSTALL_DEFAULT_BINDIR})
add_executable(hackrf_rffc5071 hackrf_rffc5071.c)
install(TARGETS hackrf_rffc5071 RUNTIME DESTINATION ${INSTALL_DEFAULT_BINDIR})
add_executable(hackrf_spiflash hackrf_spiflash.c)
install(TARGETS hackrf_spiflash RUNTIME DESTINATION ${INSTALL_DEFAULT_BINDIR})
add_executable(hackrf_cpldjtag hackrf_cpldjtag.c)
install(TARGETS hackrf_cpldjtag RUNTIME DESTINATION ${INSTALL_DEFAULT_BINDIR})
add_executable(hackrf_info hackrf_info.c)
install(TARGETS hackrf_info RUNTIME DESTINATION ${INSTALL_DEFAULT_BINDIR})
SET(TOOLS
hackrf_max2837
hackrf_si5351c
hackrf_transfer
hackrf_rffc5071
hackrf_spiflash
hackrf_cpldjtag
hackrf_info
hackrf_operacake
hackrf_sweep
)
if(NOT libhackrf_SOURCE_DIR)
include_directories(${LIBHACKRF_INCLUDE_DIR})
LIST(APPEND TOOLS_LINK_LIBS ${LIBHACKRF_LIBRARIES})
include_directories(${LIBHACKRF_INCLUDE_DIR})
LIST(APPEND TOOLS_LINK_LIBS ${LIBHACKRF_LIBRARIES})
else()
LIST(APPEND TOOLS_LINK_LIBS hackrf)
LIST(APPEND TOOLS_LINK_LIBS hackrf)
endif()
if(MSVC)
LIST(APPEND TOOLS_LINK_LIBS libgetopt_static)
LIST(APPEND TOOLS_LINK_LIBS libgetopt_static)
endif()
LIST(APPEND TOOLS_LINK_LIBS m fftw3f)
target_link_libraries(hackrf_max2837 ${TOOLS_LINK_LIBS})
target_link_libraries(hackrf_si5351c ${TOOLS_LINK_LIBS})
target_link_libraries(hackrf_transfer ${TOOLS_LINK_LIBS})
target_link_libraries(hackrf_rffc5071 ${TOOLS_LINK_LIBS})
target_link_libraries(hackrf_spiflash ${TOOLS_LINK_LIBS})
target_link_libraries(hackrf_cpldjtag ${TOOLS_LINK_LIBS})
target_link_libraries(hackrf_info ${TOOLS_LINK_LIBS})
foreach(tool ${TOOLS})
add_executable(${tool} ${tool}.c)
target_link_libraries(${tool} ${TOOLS_LINK_LIBS})
install(TARGETS ${tool} RUNTIME DESTINATION ${INSTALL_DEFAULT_BINDIR})
endforeach(tool)

View File

@ -32,9 +32,10 @@ int main(void)
uint8_t board_id = BOARD_ID_INVALID;
char version[255 + 1];
read_partid_serialno_t read_partid_serialno;
uint8_t operacakes[8];
hackrf_device_list_t *list;
hackrf_device* device;
int i;
int i, j;
result = hackrf_init();
if (result != HACKRF_SUCCESS) {
@ -99,6 +100,19 @@ int main(void)
read_partid_serialno.serial_no[2],
read_partid_serialno.serial_no[3]);
result = hackrf_get_operacake_boards(device, &operacakes[0]);
if (result != HACKRF_SUCCESS) {
fprintf(stderr, "hackrf_get_operacake_boards() failed: %s (%d)\n",
hackrf_error_name(result), result);
return EXIT_FAILURE;
}
for(j=0; j<8; j++) {
if(operacakes[j] == 0)
break;
printf("Operacake found, address: 0x%02x\n", operacakes[j]);
}
result = hackrf_close(device);
if (result != HACKRF_SUCCESS) {
fprintf(stderr, "hackrf_close() failed: %s (%d)\n",

View File

@ -0,0 +1,158 @@
/*
* Copyright 2016 Dominic Spill <dominicgs@gmail.com>
*
* This file is part of HackRF.
*
* 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 <hackrf.h>
#include <stdio.h>
#include <stdlib.h>
#include <getopt.h>
#ifndef bool
typedef int bool;
#define true 1
#define false 0
#endif
static void usage() {
printf("\nUsage:\n");
printf("\t-s, --serial <s>: specify a particular device by serial number\n");
printf("\t-d, --device <n>: specify a particular device by number\n");
printf("\t-o, --address <n>: specify a particular operacake by address [default: 0x00]\n");
printf("\t-a <n>: set port A connection\n");
printf("\t-b <n>: set port B connection\n");
printf("\t-v: verbose, list available operacake boards\n");
}
static struct option long_options[] = {
{ "device", no_argument, 0, 'd' },
{ "serial", no_argument, 0, 's' },
{ "address", no_argument, 0, 'o' },
{ 0, 0, 0, 0 },
};
int parse_int(char* const s, uint16_t* const value) {
char* s_end = s;
const long long_value = strtol(s, &s_end, 10);
if( (s != s_end) && (*s_end == 0) ) {
*value = (uint16_t)long_value;
return HACKRF_SUCCESS;
} else {
return HACKRF_ERROR_INVALID_PARAM;
}
}
int main(int argc, char** argv) {
int opt;
const char* serial_number = NULL;
int device_index = 0;
int operacake_address = 0;
int port_a = 0;
int port_b = 0;
int verbose = 0;
uint8_t operacakes[8];
int i = 0;
hackrf_device* device = NULL;
int option_index = 0;
int result = hackrf_init();
if( result ) {
printf("hackrf_init() failed: %s (%d)\n", hackrf_error_name(result), result);
return -1;
}
while( (opt = getopt_long(argc, argv, "d:s:o:a:b:v", long_options, &option_index)) != EOF ) {
switch( opt ) {
case 'd':
device_index = atoi(optarg);
break;
case 's':
serial_number = optarg;
break;
case 'o':
operacake_address = atoi(optarg);
break;
case 'a':
port_a = atoi(optarg);
break;
case 'b':
port_b = atoi(optarg);
break;
case 'v':
verbose = 1;
break;
default:
usage();
}
if( result != HACKRF_SUCCESS ) {
printf("argument error: %s (%d)\n", hackrf_error_name(result), result);
break;
}
}
if(serial_number != NULL) {
result = hackrf_open_by_serial(serial_number, &device);
} else {
hackrf_device_list_t* device_list = hackrf_device_list();
if(device_list->devicecount <= 0) {
result = HACKRF_ERROR_NOT_FOUND;
} else {
result = hackrf_device_list_open(device_list, device_index, &device);
}
}
if( result ) {
printf("hackrf_open() failed: %s (%d)\n", hackrf_error_name(result), result);
return -1;
}
if(verbose) {
hackrf_get_operacake_boards(device, operacakes);
printf("Operacakes found:\n");
for(i=0; i<8; i++) {
if(operacakes[i] !=0)
printf("%d\n", operacakes[i]);
}
printf("\n");
}
result = hackrf_set_operacake_ports(device, operacake_address, port_a, port_b);
if( result ) {
printf("hackrf_set_operacake_ports() failed: %s (%d)\n", hackrf_error_name(result), result);
return -1;
}
result = hackrf_close(device);
if( result ) {
printf("hackrf_close() failed: %s (%d)\n", hackrf_error_name(result), result);
return -1;
}
hackrf_exit();
return 0;
}

View File

@ -0,0 +1,547 @@
/*
* Copyright 2016 Dominic Spill <dominicgs@gmail.com>
* Copyright 2016 Mike Walters <mike@flomp.net>
*
* This file is part of HackRF.
*
* 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 <hackrf.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <getopt.h>
#include <time.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <errno.h>
#include <fftw3.h>
#include <math.h>
#ifndef bool
typedef int bool;
#define true 1
#define false 0
#endif
#ifdef _WIN32
#include <windows.h>
#ifdef _MSC_VER
#ifdef _WIN64
typedef int64_t ssize_t;
#else
typedef int32_t ssize_t;
#endif
#define strtoull _strtoui64
#define snprintf _snprintf
int gettimeofday(struct timeval *tv, void* ignored) {
FILETIME ft;
unsigned __int64 tmp = 0;
if (NULL != tv) {
GetSystemTimeAsFileTime(&ft);
tmp |= ft.dwHighDateTime;
tmp <<= 32;
tmp |= ft.dwLowDateTime;
tmp /= 10;
tmp -= 11644473600000000Ui64;
tv->tv_sec = (long)(tmp / 1000000UL);
tv->tv_usec = (long)(tmp % 1000000UL);
}
return 0;
}
#endif
#endif
#if defined(__GNUC__)
#include <unistd.h>
#include <sys/time.h>
#endif
#include <signal.h>
#define FD_BUFFER_SIZE (8*1024)
#define FREQ_ONE_MHZ (1000000ull)
#define FREQ_MIN_HZ (0ull) /* 0 Hz */
#define FREQ_MAX_HZ (7250000000ull) /* 7250MHz */
#define DEFAULT_SAMPLE_RATE_HZ (20000000) /* 20MHz default sample rate */
#define DEFAULT_BASEBAND_FILTER_BANDWIDTH (15000000) /* 5MHz default */
#define FREQ_STEP (DEFAULT_SAMPLE_RATE_HZ / FREQ_ONE_MHZ)
#define MAX_FREQ_COUNT 1000
#define DEFAULT_SAMPLE_COUNT 0x4000
#if defined _WIN32
#define sleep(a) Sleep( (a*1000) )
#endif
static float TimevalDiff(const struct timeval *a, const struct timeval *b) {
return (a->tv_sec - b->tv_sec) + 1e-6f * (a->tv_usec - b->tv_usec);
}
int parse_u32(char* s, uint32_t* const value) {
uint_fast8_t base = 10;
char* s_end;
uint64_t ulong_value;
if( strlen(s) > 2 ) {
if( s[0] == '0' ) {
if( (s[1] == 'x') || (s[1] == 'X') ) {
base = 16;
s += 2;
} else if( (s[1] == 'b') || (s[1] == 'B') ) {
base = 2;
s += 2;
}
}
}
s_end = s;
ulong_value = strtoul(s, &s_end, base);
if( (s != s_end) && (*s_end == 0) ) {
*value = (uint32_t)ulong_value;
return HACKRF_SUCCESS;
} else {
return HACKRF_ERROR_INVALID_PARAM;
}
}
int parse_u32_range(char* s, uint32_t* const value_min, uint32_t* const value_max) {
int result;
char *sep = strchr(s, ':');
if (!sep)
return HACKRF_ERROR_INVALID_PARAM;
*sep = 0;
result = parse_u32(s, value_min);
if (result != HACKRF_SUCCESS)
return result;
result = parse_u32(sep + 1, value_max);
if (result != HACKRF_SUCCESS)
return result;
return HACKRF_SUCCESS;
}
volatile bool do_exit = false;
FILE* fd = NULL;
volatile uint32_t byte_count = 0;
struct timeval time_start;
struct timeval t_start;
bool amp = false;
uint32_t amp_enable;
bool antenna = false;
uint32_t antenna_enable;
uint32_t freq_min;
uint32_t freq_max;
int fftSize;
fftwf_complex *fftwIn = NULL;
fftwf_complex *fftwOut = NULL;
fftwf_plan fftwPlan = NULL;
float* pwr;
float* window;
float logPower(fftwf_complex in, float scale)
{
float re = in[0] * scale;
float im = in[1] * scale;
float magsq = re * re + im * im;
return log2f(magsq) * 10.0f / log2(10.0f);
}
int rx_callback(hackrf_transfer* transfer) {
/* This is where we need to do interesting things with the samples
* FFT
* Throw away unused bins
* write output to pipe
*/
ssize_t bytes_to_write;
ssize_t bytes_written;
int8_t* buf;
float frequency;
int i, j;
if( fd != NULL ) {
byte_count += transfer->valid_length;
bytes_to_write = transfer->valid_length;
buf = (int8_t*) transfer->buffer;
for(j=0; j<16; j++) {
if(buf[0] == 0x7F && buf[1] == 0x7F) {
frequency = *(uint16_t*)&buf[2];
}
/* copy to fftwIn as floats */
buf += 16384 - (fftSize * 2);
for(i=0; i < fftSize; i++) {
fftwIn[i][0] = buf[i*2] * window[i] * 1.0f / 128.0f;
fftwIn[i][1] = buf[i*2+1] * window[i] * 1.0f / 128.0f;
}
buf += fftSize * 2;
fftwf_execute(fftwPlan);
for (i=0; i < fftSize; i++) {
// Start from the middle of the FFTW array and wrap
// to rearrange the data
int k = i ^ (fftSize >> 1);
pwr[i] = logPower(fftwOut[k], 1.0f / fftSize);
}
fwrite(&frequency, sizeof(float), 1, stdout);
fwrite(pwr, sizeof(float), fftSize, stdout);
}
bytes_written = fwrite(transfer->buffer, 1, bytes_to_write, fd);
if (bytes_written != bytes_to_write) {
return -1;
} else {
return 0;
}
} else {
return -1;
}
}
static void usage() {
fprintf(stderr, "Usage:\n");
fprintf(stderr, "\t[-d serial_number] # Serial number of desired HackRF.\n");
fprintf(stderr, "\t[-a amp_enable] # RX/TX RF amplifier 1=Enable, 0=Disable.\n");
fprintf(stderr, "\t[-f freq_min:freq_max # Specify minimum & maximum sweep frequencies (MHz).\n");
fprintf(stderr, "\t[-p antenna_enable] # Antenna port power, 1=Enable, 0=Disable.\n");
fprintf(stderr, "\t[-l gain_db] # RX LNA (IF) gain, 0-40dB, 8dB steps\n");
fprintf(stderr, "\t[-g gain_db] # RX VGA (baseband) gain, 0-62dB, 2dB steps\n");
fprintf(stderr, "\t[-x gain_db] # TX VGA (IF) gain, 0-47dB, 1dB steps\n");
fprintf(stderr, "\t[-n num_samples] # Number of samples per frequency, 0-4294967296\n");
}
static hackrf_device* device = NULL;
#ifdef _MSC_VER
BOOL WINAPI
sighandler(int signum) {
if (CTRL_C_EVENT == signum) {
fprintf(stderr, "Caught signal %d\n", signum);
do_exit = true;
return TRUE;
}
return FALSE;
}
#else
void sigint_callback_handler(int signum) {
fprintf(stderr, "Caught signal %d\n", signum);
do_exit = true;
}
#endif
int main(int argc, char** argv) {
int opt, i, result, ifreq = 0;
bool odd;
const char* path = "/dev/null";
const char* serial_number = NULL;
int exit_code = EXIT_SUCCESS;
struct timeval t_end;
float time_diff;
unsigned int lna_gain=16, vga_gain=20, txvga_gain=0;
uint16_t frequencies[MAX_FREQ_COUNT];
uint32_t num_samples = DEFAULT_SAMPLE_COUNT;
while( (opt = getopt(argc, argv, "a:f:p:l:g:x:d:n:")) != EOF ) {
result = HACKRF_SUCCESS;
switch( opt )
{
case 'd':
serial_number = optarg;
break;
case 'a':
amp = true;
result = parse_u32(optarg, &amp_enable);
break;
case 'f':
result = parse_u32_range(optarg, &freq_min, &freq_max);
fprintf(stderr, "Scanning %uMHz to %uMHz\n", freq_min, freq_max);
frequencies[ifreq++] = freq_min;
odd = true;
while(frequencies[ifreq-1] <= freq_max) {
if (odd)
frequencies[ifreq] = frequencies[ifreq-1] + FREQ_STEP / 4;
else
frequencies[ifreq] = frequencies[ifreq-1] + 3*(FREQ_STEP/4);
ifreq++;
odd = !odd;
}
break;
case 'p':
antenna = true;
result = parse_u32(optarg, &antenna_enable);
break;
case 'l':
result = parse_u32(optarg, &lna_gain);
break;
case 'g':
result = parse_u32(optarg, &vga_gain);
break;
case 'x':
result = parse_u32(optarg, &txvga_gain);
break;
case 'n':
result = parse_u32(optarg, &num_samples);
break;
default:
fprintf(stderr, "unknown argument '-%c %s'\n", opt, optarg);
usage();
return EXIT_FAILURE;
}
if( result != HACKRF_SUCCESS ) {
fprintf(stderr, "argument error: '-%c %s' %s (%d)\n", opt, optarg, hackrf_error_name(result), result);
usage();
return EXIT_FAILURE;
}
}
if (lna_gain % 8)
fprintf(stderr, "warning: lna_gain (-l) must be a multiple of 8\n");
if (vga_gain % 2)
fprintf(stderr, "warning: vga_gain (-g) must be a multiple of 2\n");
if (num_samples % 0x4000) {
fprintf(stderr, "warning: num_samples (-n) must be a multiple of 16384\n");
return EXIT_FAILURE;
}
if( amp ) {
if( amp_enable > 1 ) {
fprintf(stderr, "argument error: amp_enable shall be 0 or 1.\n");
usage();
return EXIT_FAILURE;
}
}
if (antenna) {
if (antenna_enable > 1) {
fprintf(stderr, "argument error: antenna_enable shall be 0 or 1.\n");
usage();
return EXIT_FAILURE;
}
}
if (ifreq == 0) {
fprintf(stderr, "argument error: must specify sweep frequency range (-f).\n");
usage();
return EXIT_FAILURE;
}
fftSize = 64;
fftwIn = (fftwf_complex*)fftwf_malloc(sizeof(fftwf_complex) * fftSize);
fftwOut = (fftwf_complex*)fftwf_malloc(sizeof(fftwf_complex) * fftSize);
fftwPlan = fftwf_plan_dft_1d(fftSize, fftwIn, fftwOut, FFTW_FORWARD, FFTW_MEASURE);
pwr = (float*)fftwf_malloc(sizeof(float) * fftSize);
window = (float*)fftwf_malloc(sizeof(float) * fftSize);
for (i = 0; i < fftSize; i++) {
window[i] = 0.5f * (1.0f - cos(2 * M_PI * i / (fftSize - 1)));
}
result = hackrf_init();
if( result != HACKRF_SUCCESS ) {
fprintf(stderr, "hackrf_init() failed: %s (%d)\n", hackrf_error_name(result), result);
usage();
return EXIT_FAILURE;
}
result = hackrf_open_by_serial(serial_number, &device);
if( result != HACKRF_SUCCESS ) {
fprintf(stderr, "hackrf_open() failed: %s (%d)\n", hackrf_error_name(result), result);
usage();
return EXIT_FAILURE;
}
fd = fopen(path, "wb");
if( fd == NULL ) {
fprintf(stderr, "Failed to open file: %s\n", path);
return EXIT_FAILURE;
}
/* Change fd buffer to have bigger one to store or read data on/to HDD */
result = setvbuf(fd , NULL , _IOFBF , FD_BUFFER_SIZE);
if( result != 0 ) {
fprintf(stderr, "setvbuf() failed: %d\n", result);
usage();
return EXIT_FAILURE;
}
#ifdef _MSC_VER
SetConsoleCtrlHandler( (PHANDLER_ROUTINE) sighandler, TRUE );
#else
signal(SIGINT, &sigint_callback_handler);
signal(SIGILL, &sigint_callback_handler);
signal(SIGFPE, &sigint_callback_handler);
signal(SIGSEGV, &sigint_callback_handler);
signal(SIGTERM, &sigint_callback_handler);
signal(SIGABRT, &sigint_callback_handler);
#endif
fprintf(stderr, "call hackrf_sample_rate_set(%.03f MHz)\n",
((float)DEFAULT_SAMPLE_RATE_HZ/(float)FREQ_ONE_MHZ));
result = hackrf_set_sample_rate_manual(device, DEFAULT_SAMPLE_RATE_HZ, 1);
if( result != HACKRF_SUCCESS ) {
fprintf(stderr, "hackrf_sample_rate_set() failed: %s (%d)\n",
hackrf_error_name(result), result);
usage();
return EXIT_FAILURE;
}
fprintf(stderr, "call hackrf_baseband_filter_bandwidth_set(%.03f MHz)\n",
((float)DEFAULT_BASEBAND_FILTER_BANDWIDTH/(float)FREQ_ONE_MHZ));
result = hackrf_set_baseband_filter_bandwidth(device, DEFAULT_BASEBAND_FILTER_BANDWIDTH);
if( result != HACKRF_SUCCESS ) {
fprintf(stderr, "hackrf_baseband_filter_bandwidth_set() failed: %s (%d)\n",
hackrf_error_name(result), result);
usage();
return EXIT_FAILURE;
}
result = hackrf_set_vga_gain(device, vga_gain);
result |= hackrf_set_lna_gain(device, lna_gain);
result |= hackrf_start_rx(device, rx_callback, NULL);
if (result != HACKRF_SUCCESS) {
fprintf(stderr, "hackrf_start_?x() failed: %s (%d)\n", hackrf_error_name(result), result);
usage();
return EXIT_FAILURE;
}
result = hackrf_init_sweep(device, frequencies, ifreq, num_samples);
if( result != HACKRF_SUCCESS ) {
fprintf(stderr, "hackrf_init_sweep() failed: %s (%d)\n",
hackrf_error_name(result), result);
usage();
return EXIT_FAILURE;
}
if (amp) {
fprintf(stderr, "call hackrf_set_amp_enable(%u)\n", amp_enable);
result = hackrf_set_amp_enable(device, (uint8_t)amp_enable);
if (result != HACKRF_SUCCESS) {
fprintf(stderr, "hackrf_set_amp_enable() failed: %s (%d)\n",
hackrf_error_name(result), result);
usage();
return EXIT_FAILURE;
}
}
if (antenna) {
fprintf(stderr, "call hackrf_set_antenna_enable(%u)\n", antenna_enable);
result = hackrf_set_antenna_enable(device, (uint8_t)antenna_enable);
if (result != HACKRF_SUCCESS) {
fprintf(stderr, "hackrf_set_antenna_enable() failed: %s (%d)\n",
hackrf_error_name(result), result);
usage();
return EXIT_FAILURE;
}
}
gettimeofday(&t_start, NULL);
gettimeofday(&time_start, NULL);
fprintf(stderr, "Stop with Ctrl-C\n");
while((hackrf_is_streaming(device) == HACKRF_TRUE) && (do_exit == false)) {
uint32_t byte_count_now;
struct timeval time_now;
float time_difference, rate;
sleep(1);
gettimeofday(&time_now, NULL);
byte_count_now = byte_count;
byte_count = 0;
time_difference = TimevalDiff(&time_now, &time_start);
rate = (float)byte_count_now / time_difference;
fprintf(stderr, "%4.1f MiB / %5.3f sec = %4.1f MiB/second\n",
(byte_count_now / 1e6f), time_difference, (rate / 1e6f) );
time_start = time_now;
if (byte_count_now == 0) {
exit_code = EXIT_FAILURE;
fprintf(stderr, "\nCouldn't transfer any bytes for one second.\n");
break;
}
}
result = hackrf_is_streaming(device);
if (do_exit) {
fprintf(stderr, "\nUser cancel, exiting...\n");
} else {
fprintf(stderr, "\nExiting... hackrf_is_streaming() result: %s (%d)\n",
hackrf_error_name(result), result);
}
gettimeofday(&t_end, NULL);
time_diff = TimevalDiff(&t_end, &t_start);
fprintf(stderr, "Total time: %5.5f s\n", time_diff);
if(device != NULL) {
result = hackrf_stop_rx(device);
if(result != HACKRF_SUCCESS) {
fprintf(stderr, "hackrf_stop_rx() failed: %s (%d)\n",
hackrf_error_name(result), result);
} else {
fprintf(stderr, "hackrf_stop_rx() done\n");
}
result = hackrf_close(device);
if(result != HACKRF_SUCCESS) {
fprintf(stderr, "hackrf_close() failed: %s (%d)\n",
hackrf_error_name(result), result);
} else {
fprintf(stderr, "hackrf_close() done\n");
}
hackrf_exit();
fprintf(stderr, "hackrf_exit() done\n");
}
if(fd != NULL) {
fclose(fd);
fd = NULL;
fprintf(stderr, "fclose(fd) done\n");
}
fprintf(stderr, "exit\n");
return exit_code;
}

View File

@ -83,16 +83,16 @@ int gettimeofday(struct timeval *tv, void* ignored)
#define FD_BUFFER_SIZE (8*1024)
#define FREQ_ONE_MHZ (1000000ull)
#define FREQ_ONE_MHZ (1000000ll)
#define DEFAULT_FREQ_HZ (900000000ull) /* 900MHz */
#define DEFAULT_FREQ_HZ (900000000ll) /* 900MHz */
#define FREQ_MIN_HZ (0ull) /* 0 Hz */
#define FREQ_MAX_HZ (7250000000ull) /* 7250MHz */
#define IF_MIN_HZ (2150000000ull)
#define IF_MAX_HZ (2750000000ull)
#define LO_MIN_HZ (84375000ull)
#define LO_MAX_HZ (5400000000ull)
#define DEFAULT_LO_HZ (1000000000ull)
#define FREQ_MAX_HZ (7250000000ll) /* 7250MHz */
#define IF_MIN_HZ (2150000000ll)
#define IF_MAX_HZ (2750000000ll)
#define LO_MIN_HZ (84375000ll)
#define LO_MAX_HZ (5400000000ll)
#define DEFAULT_LO_HZ (1000000000ll)
#define DEFAULT_SAMPLE_RATE_HZ (10000000) /* 10MHz default sample rate */
@ -107,6 +107,18 @@ int gettimeofday(struct timeval *tv, void* ignored)
#define sleep(a) Sleep( (a*1000) )
#endif
typedef enum {
TRANSCEIVER_MODE_OFF = 0,
TRANSCEIVER_MODE_RX = 1,
TRANSCEIVER_MODE_TX = 2,
TRANSCEIVER_MODE_SS = 3,
} transceiver_mode_t;
typedef enum {
HW_SYNC_MODE_OFF = 0,
HW_SYNC_MODE_ON = 1,
} hw_sync_mode_t;
/* WAVE or RIFF WAVE file format containing IQ 2x8bits data for HackRF compatible with SDR# Wav IQ file */
typedef struct
{
@ -296,6 +308,8 @@ volatile uint32_t byte_count = 0;
bool signalsource = false;
uint32_t amplitude = 0;
bool hw_sync = false;
bool receive = false;
bool receive_wav = false;
uint64_t stream_size = 0;
@ -309,13 +323,13 @@ struct timeval time_start;
struct timeval t_start;
bool automatic_tuning = false;
uint64_t freq_hz;
int64_t freq_hz;
bool if_freq = false;
uint64_t if_freq_hz;
int64_t if_freq_hz;
bool lo_freq = false;
uint64_t lo_freq_hz = DEFAULT_LO_HZ;
int64_t lo_freq_hz = DEFAULT_LO_HZ;
bool image_reject = false;
uint32_t image_reject_selection;
@ -477,6 +491,7 @@ static void usage() {
printf("\t[-R] # Repeat TX mode (default is off) \n");
printf("\t[-b baseband_filter_bw_hz] # Set baseband filter bandwidth in Hz.\n\tPossible values: 1.75/2.5/3.5/5/5.5/6/7/8/9/10/12/14/15/20/24/28MHz, default < sample_rate_hz.\n" );
printf("\t[-C ppm] # Set Internal crystal clock error in ppm.\n");
printf("\t[-H] # Synchronise USB transfer using GPIO pins.\n");
}
static hackrf_device* device = NULL;
@ -520,11 +535,14 @@ int main(int argc, char** argv) {
float time_diff;
unsigned int lna_gain=8, vga_gain=20, txvga_gain=0;
while( (opt = getopt(argc, argv, "wr:t:f:i:o:m:a:p:s:n:b:l:g:x:c:d:C:RS:")) != EOF )
while( (opt = getopt(argc, argv, "Hwr:t:f:i:o:m:a:p:s:n:b:l:g:x:c:d:C:RS:")) != EOF )
{
result = HACKRF_SUCCESS;
switch( opt )
{
case 'H':
hw_sync = true;
break;
case 'w':
receive_wav = true;
break;
@ -718,7 +736,7 @@ int main(int argc, char** argv) {
freq_hz = if_freq_hz;
break;
case RF_PATH_FILTER_LOW_PASS:
freq_hz = abs(if_freq_hz - lo_freq_hz);
freq_hz = labs(if_freq_hz - lo_freq_hz);
break;
case RF_PATH_FILTER_HIGH_PASS:
freq_hz = if_freq_hz + lo_freq_hz;
@ -936,6 +954,15 @@ int main(int argc, char** argv) {
return EXIT_FAILURE;
}
fprintf(stderr, "call hackrf_set_hw_sync_mode(%d)\n",
hw_sync);
result = hackrf_set_hw_sync_mode(device, hw_sync ? HW_SYNC_MODE_ON : HW_SYNC_MODE_OFF);
if( result != HACKRF_SUCCESS ) {
fprintf(stderr, "hackrf_set_hw_sync_mode() failed: %s (%d)\n", hackrf_error_name(result), result);
usage();
return EXIT_FAILURE;
}
if( transceiver_mode == TRANSCEIVER_MODE_RX ) {
result = hackrf_set_vga_gain(device, vga_gain);
result |= hackrf_set_lna_gain(device, lna_gain);

View File

@ -67,6 +67,11 @@ typedef enum {
HACKRF_VENDOR_REQUEST_SET_TXVGA_GAIN = 21,
HACKRF_VENDOR_REQUEST_ANTENNA_ENABLE = 23,
HACKRF_VENDOR_REQUEST_SET_FREQ_EXPLICIT = 24,
// USB_WCID_VENDOR_REQ = 25
HACKRF_VENDOR_REQUEST_INIT_SWEEP = 26,
HACKRF_VENDOR_REQUEST_OPERACAKE_GET_BOARDS = 27,
HACKRF_VENDOR_REQUEST_OPERACAKE_SET_PORTS = 28,
HACKRF_VENDOR_REQUEST_SET_HW_SYNC_MODE = 29,
} hackrf_vendor_request;
typedef enum {
@ -78,8 +83,15 @@ typedef enum {
HACKRF_TRANSCEIVER_MODE_OFF = 0,
HACKRF_TRANSCEIVER_MODE_RECEIVE = 1,
HACKRF_TRANSCEIVER_MODE_TRANSMIT = 2,
HACKRF_TRANSCEIVER_MODE_SS = 3,
TRANSCEIVER_MODE_CPLD_UPDATE = 4,
} hackrf_transceiver_mode;
typedef enum {
HACKRF_HW_SYNC_MODE_OFF = 0,
HACKRF_HW_SYNC_MODE_ON = 1,
} hackrf_hw_sync_mode;
struct hackrf_device {
libusb_device_handle* usb_device;
struct libusb_transfer** transfers;
@ -384,7 +396,7 @@ hackrf_device_list_t* ADDCALL hackrf_device_list()
serial_number_length = libusb_get_string_descriptor_ascii(usb_device, serial_descriptor_index, (unsigned char*)serial_number, sizeof(serial_number));
if( serial_number_length == 32 ) {
serial_number[32] = 0;
list->serial_numbers[idx] = strdup(serial_number);
list->serial_numbers[idx] = strndup(serial_number, serial_number_length);
}
libusb_close(usb_device);
@ -1415,6 +1427,7 @@ static int create_transfer_thread(hackrf_device* device,
if( device->transfer_thread_started == false )
{
device->streaming = false;
do_exit = false;
result = prepare_transfers(
device, endpoint_address,
@ -1546,6 +1559,26 @@ int ADDCALL hackrf_close(hackrf_device* device)
return result1;
}
int ADDCALL hackrf_set_hw_sync_mode(hackrf_device* device, const uint8_t value) {
int result = libusb_control_transfer(
device->usb_device,
LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE,
HACKRF_VENDOR_REQUEST_SET_HW_SYNC_MODE,
value,
0,
NULL,
0,
0
);
if( result != 0 )
{
return HACKRF_ERROR_LIBUSB;
} else {
return HACKRF_SUCCESS;
}
}
const char* ADDCALL hackrf_error_name(enum hackrf_error errcode)
{
switch(errcode)
@ -1604,6 +1637,9 @@ const char* ADDCALL hackrf_board_id_name(enum hackrf_board_id board_id)
case BOARD_ID_HACKRF_ONE:
return "HackRF One";
case BOARD_ID_RAD1O:
return "rad1o";
case BOARD_ID_INVALID:
return "Invalid Board ID";
@ -1622,6 +1658,9 @@ extern ADDAPI const char* ADDCALL hackrf_usb_board_id_name(enum hackrf_usb_board
case USB_BOARD_ID_HACKRF_ONE:
return "HackRF One";
case USB_BOARD_ID_RAD1O:
return "rad1o";
case USB_BOARD_ID_INVALID:
return "Invalid Board ID";
@ -1687,6 +1726,92 @@ uint32_t ADDCALL hackrf_compute_baseband_filter_bw(const uint32_t bandwidth_hz)
return p->bandwidth_hz;
}
/* Initialise sweep mode with alist of frequencies and dwell time in samples */
int ADDCALL hackrf_init_sweep(hackrf_device* device, uint16_t* frequency_list, int length, uint32_t dwell_time)
{
int result, i;
int size = length * sizeof(frequency_list[0]);
for(i=0; i<length; i++)
frequency_list[i] = TO_LE(frequency_list[i]);
result = libusb_control_transfer(
device->usb_device,
LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE,
HACKRF_VENDOR_REQUEST_INIT_SWEEP,
dwell_time & 0xffff,
(dwell_time >> 16) & 0xffff,
(unsigned char*)frequency_list,
size,
0
);
if (result < size) {
return HACKRF_ERROR_LIBUSB;
} else {
return HACKRF_SUCCESS;
}
}
/* Retrieve list of Operacake board addresses
* boards must be *uint8_t[8]
*/
int ADDCALL hackrf_get_operacake_boards(hackrf_device* device, uint8_t* boards)
{
int result;
result = libusb_control_transfer(
device->usb_device,
LIBUSB_ENDPOINT_IN | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE,
HACKRF_VENDOR_REQUEST_OPERACAKE_GET_BOARDS,
0,
0,
boards,
8,
0
);
if (result < 8)
{
return HACKRF_ERROR_LIBUSB;
} else {
return HACKRF_SUCCESS;
}
}
/* Set Operacake ports */
int ADDCALL hackrf_set_operacake_ports(hackrf_device* device,
uint8_t address,
uint8_t port_a,
uint8_t port_b)
{
int result;
/* Error checking */
if((port_a > OPERACAKE_PB4) || (port_b > OPERACAKE_PB4)) {
return HACKRF_ERROR_INVALID_PARAM;
}
/* Check which side PA and PB are on */
if(((port_a <= OPERACAKE_PA4) && (port_b <= OPERACAKE_PA4))
|| ((port_a > OPERACAKE_PA4) && (port_b > OPERACAKE_PA4))) {
return HACKRF_ERROR_INVALID_PARAM;
}
result = libusb_control_transfer(
device->usb_device,
LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE,
HACKRF_VENDOR_REQUEST_OPERACAKE_SET_PORTS,
address,
port_a | (port_b<<8),
NULL,
0,
0
);
if (result != 0) {
return HACKRF_ERROR_LIBUSB;
} else {
return HACKRF_SUCCESS;
}
}
#ifdef __cplusplus
} // __cplusplus defined.
#endif

View File

@ -66,6 +66,7 @@ enum hackrf_board_id {
BOARD_ID_JELLYBEAN = 0,
BOARD_ID_JAWBREAKER = 1,
BOARD_ID_HACKRF_ONE = 2,
BOARD_ID_RAD1O = 3,
BOARD_ID_INVALID = 0xFF,
};
@ -82,13 +83,16 @@ enum rf_path_filter {
RF_PATH_FILTER_HIGH_PASS = 2,
};
typedef enum {
TRANSCEIVER_MODE_OFF = 0,
TRANSCEIVER_MODE_RX = 1,
TRANSCEIVER_MODE_TX = 2,
TRANSCEIVER_MODE_SS = 3,
TRANSCEIVER_MODE_CPLD_UPDATE = 4
} transceiver_mode_t;
enum operacake_ports {
OPERACAKE_PA1 = 0,
OPERACAKE_PA2 = 1,
OPERACAKE_PA3 = 2,
OPERACAKE_PA4 = 3,
OPERACAKE_PB1 = 4,
OPERACAKE_PB2 = 5,
OPERACAKE_PB3 = 6,
OPERACAKE_PB4 = 7,
};
typedef struct hackrf_device hackrf_device;
@ -194,6 +198,9 @@ extern ADDAPI int ADDCALL hackrf_set_txvga_gain(hackrf_device* device, uint32_t
/* antenna port power control */
extern ADDAPI int ADDCALL hackrf_set_antenna_enable(hackrf_device* device, const uint8_t value);
/* set hardware sync mode */
extern ADDAPI int ADDCALL hackrf_set_hw_sync_mode(hackrf_device* device, const uint8_t value);
extern ADDAPI const char* ADDCALL hackrf_error_name(enum hackrf_error errcode);
extern ADDAPI const char* ADDCALL hackrf_board_id_name(enum hackrf_board_id board_id);
extern ADDAPI const char* ADDCALL hackrf_usb_board_id_name(enum hackrf_usb_board_id usb_board_id);
@ -203,6 +210,17 @@ extern ADDAPI const char* ADDCALL hackrf_filter_path_name(const enum rf_path_fil
extern ADDAPI uint32_t ADDCALL hackrf_compute_baseband_filter_bw_round_down_lt(const uint32_t bandwidth_hz);
/* Compute best default value depending on sample rate (auto filter) */
extern ADDAPI uint32_t ADDCALL hackrf_compute_baseband_filter_bw(const uint32_t bandwidth_hz);
/* Start scan mode */
extern ADDAPI int ADDCALL hackrf_init_sweep(hackrf_device* device,
uint16_t* frequency_list,
int length, uint32_t dwell_time);
/* Operacake functions */
int ADDCALL hackrf_get_operacake_boards(hackrf_device* device, uint8_t* boards);
int ADDCALL hackrf_set_operacake_ports(hackrf_device* device,
uint8_t address,
uint8_t port_a,
uint8_t port_b);
#ifdef __cplusplus
} // __cplusplus defined.

View File

@ -1,53 +0,0 @@
#!/usr/bin/env python
#
# Copyright 2012 Jared Boone
#
# This file is part of HackRF.
#
# 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.
#
import usb
import struct
import sys
device = usb.core.find(idVendor=0x1d50, idProduct=0x604b)
if device:
print 'Find: HackRF Jawbreaker'
else:
device = usb.core.find(idVendor=0x1d50, idProduct=0x6089)
if device:
print 'Find: HackRF One'
else:
device = usb.core.find(idVendor=0x1d50, idProduct=0xcc15)
if device:
print 'Find: rad1o'
else:
print 'Not find any HackRF device.'
sys.exit()
device.set_configuration()
def read_max2837_register(register_number):
return struct.unpack('<H', device.ctrl_transfer(0xC0, 3, 0, register_number, 2))[0]
def write_max2837_register(register_number, value):
device.ctrl_transfer(0x40, 2, value, register_number)
def dump_max2837():
for i in range(32):
print('%2d: %03x' % (i, read_max2837_register(i)))
dump_max2837()

View File

@ -1,54 +0,0 @@
#!/usr/bin/env python
#
# Copyright 2012 Jared Boone
#
# This file is part of HackRF.
#
# 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.
#
import sys
import usb
device = usb.core.find(idVendor=0x1d50, idProduct=0x604b)
if device:
print 'Find: HackRF Jawbreaker'
else:
device = usb.core.find(idVendor=0x1d50, idProduct=0x6089)
if device:
print 'Find: HackRF One'
else:
device = usb.core.find(idVendor=0x1d50, idProduct=0xcc15)
if device:
print 'Find: rad1o'
else:
print 'Not find any HackRF device.'
sys.exit()
device.set_configuration()
def set_rx():
device.ctrl_transfer(0x40, 1, 1, 0)
def set_tx():
device.ctrl_transfer(0x40, 1, 2, 0)
if len(sys.argv) == 2:
if sys.argv[1] == 'tx':
set_tx()
elif sys.argv[1] == 'rx':
set_rx()
else:
print 'Usage: %s [rx|tx]' % sys.argv[0]