Add software

This commit is contained in:
RocketGod
2022-09-22 09:26:57 -07:00
parent fee0ab05fd
commit 957ea3d712
4511 changed files with 1943182 additions and 0 deletions

View File

@ -0,0 +1,91 @@
# Copyright 2012 Jared Boone <jared@sharebrained.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.
#
cmake_minimum_required(VERSION 3.1.3)
set(CMAKE_TOOLCHAIN_FILE ../toolchain-arm-cortex-m.cmake)
project(hackrf_usb C)
include(../hackrf-common.cmake)
add_custom_command(
OUTPUT ${PATH_HACKRF_CPLD_DATA_C}
COMMAND ${PATH_CPLD_BITSTREAM_TOOL} --xsvf ${PATH_HACKRF_CPLD_XSVF} --hackrf-data ${PATH_HACKRF_CPLD_DATA_C}
DEPENDS ${PATH_CPLD_BITSTREAM_TOOL} ${PATH_HACKRF_CPLD_XSVF}
)
set(SRC_M4
hackrf_usb.c
"${PATH_HACKRF_FIRMWARE_COMMON}/tuning.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/streaming.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/usb.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/usb_request.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/usb_standard_request.c"
usb_descriptor.c
usb_device.c
usb_endpoint.c
usb_api_board_info.c
usb_api_cpld.c
usb_api_m0_state.c
usb_api_register.c
usb_api_spiflash.c
usb_api_transceiver.c
usb_api_operacake.c
usb_api_sweep.c
usb_api_ui.c
"${PATH_HACKRF_FIRMWARE_COMMON}/usb_queue.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/fault_handler.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/cpld_jtag.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/cpld_xc2c.c"
"${PATH_HACKRF_CPLD_DATA_C}"
"${PATH_HACKRF_FIRMWARE_COMMON}/xapp058/lenval.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/xapp058/micro.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/xapp058/ports.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/crc.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/rom_iap.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/operacake.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/operacake_sctimer.c"
)
set(SRC_M0 sgpio_m0.s)
if(BOARD STREQUAL "HACKRF_ONE")
SET(SRC_M4
${SRC_M4}
"${PATH_HACKRF_FIRMWARE_COMMON}/portapack.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/ui_portapack.c"
)
endif()
if(BOARD STREQUAL "RAD1O")
SET(SRC_M4
${SRC_M4}
"${PATH_HACKRF_FIRMWARE_COMMON}/rad1o/display.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/rad1o/print.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/rad1o/render.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/rad1o/decoder.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/rad1o/smallfonts.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/rad1o/draw.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/rad1o/ubuntu18.c"
"${PATH_HACKRF_FIRMWARE_COMMON}/ui_rad1o.c"
)
endif()
DeclareTargets()

View File

@ -0,0 +1,304 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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 <stddef.h>
#include <string.h>
#include <libopencm3/lpc43xx/ipc.h>
#include <libopencm3/lpc43xx/m4/nvic.h>
#include <libopencm3/lpc43xx/rgu.h>
#include <streaming.h>
#include "tuning.h"
#include "usb.h"
#include "usb_standard_request.h"
#include <rom_iap.h>
#include "usb_descriptor.h"
#include "usb_device.h"
#include "usb_endpoint.h"
#include "usb_api_board_info.h"
#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 "usb_api_ui.h"
#include "usb_bulk_buffer.h"
#include "usb_api_m0_state.h"
#include "cpld_xc2c.h"
#include "portapack.h"
#include "hackrf_ui.h"
extern uint32_t __m0_start__;
extern uint32_t __m0_end__;
extern uint32_t __ram_m0_start__;
extern uint32_t _etext_ram, _text_ram, _etext_rom;
static usb_request_handler_fn vendor_request_handler[] = {
NULL,
usb_vendor_request_set_transceiver_mode,
usb_vendor_request_write_max2837,
usb_vendor_request_read_max2837,
usb_vendor_request_write_si5351c,
usb_vendor_request_read_si5351c,
usb_vendor_request_set_sample_rate_frac,
usb_vendor_request_set_baseband_filter_bandwidth,
#ifdef RAD1O
NULL, // write_rffc5071 not used
NULL, // read_rffc5071 not used
#else
usb_vendor_request_write_rffc5071,
usb_vendor_request_read_rffc5071,
#endif
usb_vendor_request_erase_spiflash,
usb_vendor_request_write_spiflash,
usb_vendor_request_read_spiflash,
NULL, // used to be write_cpld
usb_vendor_request_read_board_id,
usb_vendor_request_read_version_string,
usb_vendor_request_set_freq,
usb_vendor_request_set_amp_enable,
usb_vendor_request_read_partid_serialno,
usb_vendor_request_set_lna_gain,
usb_vendor_request_set_vga_gain,
usb_vendor_request_set_txvga_gain,
NULL, // was set_if_freq
#ifdef HACKRF_ONE
usb_vendor_request_set_antenna_enable,
#else
NULL,
#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,
usb_vendor_request_reset,
usb_vendor_request_operacake_set_ranges,
usb_vendor_request_set_clkout_enable,
usb_vendor_request_spiflash_status,
usb_vendor_request_spiflash_clear_status,
usb_vendor_request_operacake_gpio_test,
#ifdef HACKRF_ONE
usb_vendor_request_cpld_checksum,
#else
NULL,
#endif
usb_vendor_request_set_ui_enable,
usb_vendor_request_operacake_set_mode,
usb_vendor_request_operacake_get_mode,
usb_vendor_request_operacake_set_dwell_times,
usb_vendor_request_get_m0_state,
usb_vendor_request_set_tx_underrun_limit,
usb_vendor_request_set_rx_overrun_limit,
};
static const uint32_t vendor_request_handler_count =
sizeof(vendor_request_handler) / sizeof(vendor_request_handler[0]);
usb_request_status_t usb_vendor_request(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
usb_request_status_t status = USB_REQUEST_STATUS_STALL;
if( endpoint->setup.request < vendor_request_handler_count ) {
usb_request_handler_fn handler = vendor_request_handler[endpoint->setup.request];
if( handler ) {
status = handler(endpoint, stage);
}
}
return status;
}
const usb_request_handlers_t usb_request_handlers = {
.standard = usb_standard_request,
.class = 0,
.vendor = usb_vendor_request,
.reserved = 0,
};
void usb_configuration_changed(
usb_device_t* const device
) {
/* Reset transceiver to idle state until other commands are received */
request_transceiver_mode(TRANSCEIVER_MODE_OFF);
if( device->configuration->number == 1 ) {
// transceiver configuration
led_on(LED1);
} else {
/* Configuration number equal 0 means usb bus reset. */
led_off(LED1);
}
usb_endpoint_init(&usb_endpoint_bulk_in);
usb_endpoint_init(&usb_endpoint_bulk_out);
}
void usb_set_descriptor_by_serial_number(void)
{
iap_cmd_res_t iap_cmd_res;
/* Read IAP Serial Number Identification */
iap_cmd_res.cmd_param.command_code = IAP_CMD_READ_SERIAL_NO;
iap_cmd_call(&iap_cmd_res);
if (iap_cmd_res.status_res.status_ret == CMD_SUCCESS) {
usb_descriptor_string_serial_number[0] = USB_DESCRIPTOR_STRING_SERIAL_BUF_LEN;
usb_descriptor_string_serial_number[1] = USB_DESCRIPTOR_TYPE_STRING;
/* 32 characters of serial number, convert to UTF-16LE */
for (size_t i=0; i<USB_DESCRIPTOR_STRING_SERIAL_LEN; i++) {
const uint_fast8_t nibble = (iap_cmd_res.status_res.iap_result[i >> 3] >> (28 - (i & 7) * 4)) & 0xf;
const char c = (nibble > 9) ? ('a' + nibble - 10) : ('0' + nibble);
usb_descriptor_string_serial_number[2 + i * 2] = c;
usb_descriptor_string_serial_number[3 + i * 2] = 0x00;
}
} else {
usb_descriptor_string_serial_number[0] = 2;
usb_descriptor_string_serial_number[1] = USB_DESCRIPTOR_TYPE_STRING;
}
}
static bool cpld_jtag_sram_load(jtag_t* const jtag) {
cpld_jtag_take(jtag);
cpld_xc2c64a_jtag_sram_write(jtag, &cpld_hackrf_program_sram);
const bool success = cpld_xc2c64a_jtag_sram_verify(jtag, &cpld_hackrf_program_sram, &cpld_hackrf_verify);
cpld_jtag_release(jtag);
return success;
}
static void m0_rom_to_ram() {
uint32_t *dest = &__ram_m0_start__;
// Calculate the base address of ROM
uint32_t base = (uint32_t)(&_etext_rom - (&_etext_ram - &_text_ram));
// M0 image location, relative to the start of ROM
uint32_t src = (uint32_t)&__m0_start__;
uint32_t len = (uint32_t)&__m0_end__ - (uint32_t)src;
memcpy(dest, (uint32_t*)(base + src), len);
}
int main(void) {
// Copy M0 image from ROM before SPIFI is disabled
m0_rom_to_ram();
pin_setup();
enable_1v8_power();
#if (defined HACKRF_ONE || defined RAD1O)
enable_rf_power();
/* Let the voltage stabilize */
delay(1000000);
#endif
cpu_clock_init();
/* Wake the M0 */
ipc_start_m0((uint32_t)&__ram_m0_start__);
if( !cpld_jtag_sram_load(&jtag_cpld) ) {
halt_and_flash(6000000);
}
#ifdef HACKRF_ONE
portapack_init();
#endif
#ifndef DFU_MODE
usb_set_descriptor_by_serial_number();
#endif
usb_set_configuration_changed_cb(usb_configuration_changed);
usb_peripheral_reset();
usb_device_init(0, &usb_device);
usb_queue_init(&usb_endpoint_control_out_queue);
usb_queue_init(&usb_endpoint_control_in_queue);
usb_queue_init(&usb_endpoint_bulk_out_queue);
usb_queue_init(&usb_endpoint_bulk_in_queue);
usb_endpoint_init(&usb_endpoint_control_out);
usb_endpoint_init(&usb_endpoint_control_in);
nvic_set_priority(NVIC_USB0_IRQ, 255);
hackrf_ui()->init();
usb_run(&usb_device);
rf_path_init(&rf_path);
bool operacake_allow_gpio;
if( hackrf_ui()->operacake_gpio_compatible() ) {
operacake_allow_gpio = true;
} else {
operacake_allow_gpio = false;
}
operacake_init(operacake_allow_gpio);
while(true) {
transceiver_request_t request;
// Briefly disable USB interrupt so that we can
// atomically retrieve both the transceiver mode
// and the mode change sequence number. They are
// changed together by request_transceiver_mode()
// called from the USB ISR.
nvic_disable_irq(NVIC_USB0_IRQ);
request = transceiver_request;
nvic_enable_irq(NVIC_USB0_IRQ);
switch (request.mode) {
case TRANSCEIVER_MODE_OFF:
off_mode(request.seq);
break;
case TRANSCEIVER_MODE_RX:
rx_mode(request.seq);
break;
case TRANSCEIVER_MODE_TX:
tx_mode(request.seq);
break;
case TRANSCEIVER_MODE_RX_SWEEP:
sweep_mode(request.seq);
break;
case TRANSCEIVER_MODE_CPLD_UPDATE:
cpld_update();
break;
default:
break;
}
}
return 0;
}

View File

@ -0,0 +1,698 @@
/*
* Copyright 2019-2022 Great Scott Gadgets
*
* 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.
*/
/*
Introduction
============
This file contains the code that runs on the Cortex-M0 core of the LPC43xx.
The M0 core is used to implement all the timing-critical usage of the SGPIO
peripheral, which interfaces to the MAX5864 ADC/DAC via the CPLD.
The M0 reads or writes 32 bytes at a time from the SGPIO registers,
transferring these bytes to or from a shared USB bulk buffer. The M4 core
handles transferring data between this buffer and the USB host.
The SGPIO peripheral is set up and enabled by the M4 core. All the M0 needs to
do is handle the SGPIO exchange interrupt, which indicates that new data can
now be read from or written to the SGPIO shadow registers.
To implement the different functions of HackRF, the M0 operates in one of
five modes, configured by the M4:
IDLE: Do nothing.
WAIT: Do nothing, but increment byte counter for timing purposes.
RX: Read data from SGPIO and write it to the buffer.
TX_START: Write zeroes to SGPIO until there is data in the buffer.
TX_RUN: Read data from the buffer and write it to SGPIO.
In all modes except IDLE, the M0 advances a byte counter, which increases by
32 each time that many bytes are exchanged with the buffer (or skipped over,
in WAIT mode).
As the M4 core produces or consumes these bytes, it advances its own counter.
The difference between the two counter values therefore indicates the number
of bytes available.
If the M4 does not advance its count in time, a TX underrun or RX overrun
occurs. Collectively, these events are referred to as shortfalls, and the
handling is similar for both.
In an RX shortfall, data is discarded. In TX mode, zeroes are written to
SGPIO. When in a shortfall, the byte counter does not advance.
The M0 maintains statistics on the the number of shortfalls, and the length of
the longest shortfall.
The M0 can be configured to abort TX or RX and return to IDLE mode, if the
length of a shortfall exceeds a configured limit.
The M0 can also be configured to switch modes automatically when its byte
counter matches a threshold value. This feature can be used to implement
timed operations.
Timing
======
This code has tight timing constraints.
We have to complete a read or write from SGPIO every 163 cycles.
The CPU clock is 204MHz. We exchange 32 bytes at a time in the SGPIO
registers, which is 16 samples worth of IQ data. At the maximum sample rate of
20MHz, the SGPIO update rate is 20 / 16 = 1.25MHz. So we have 204 / 1.25 =
163.2 cycles available.
Access to the SGPIO peripheral is slow, due to the asynchronous bridge that
connects it to the AHB bus matrix. Section 20.4.1 of the LPC43xx user manual
(UM10503) specifies the access latencies as:
Read: 4 x MCLK + 4 x CLK_PERIPH_SGPIO
Write: 4 x MCLK + 2 x CLK_PERIPH_SGPIO
In our case both these clocks are at 204MHz so reads add 8 cycles and writes
add 6. These are latencies that add to the usual M0 instruction timings, so an
ldr from SGPIO takes 10 cycles, and an str to SGPIO takes 8 cycles.
These latencies are assumed to apply to all accesses to the SGPIO peripheral's
address space, which includes its interrupt control registers as well as the
shadow registers.
There are four key code paths, with the following worst-case timings:
RX, normal: 152 cycles
RX, overrun: 76 cycles
TX, normal: 140 cycles
TX, underrun: 145 cycles
Design
======
Due to the timing constraints, this code is highly optimised.
This is the only code that runs on the M0, so it does not need to follow
calling conventions, nor use features of the architecture in standard ways.
The SGPIO handling does not run as an ISR. It polls the interrupt status.
This saves the cycle costs of interrupt entry and exit, and allows all
registers to be used freely.
All possible registers, including the stack pointer and link register, can be
used to store values needed in the code, to minimise memory loads and stores.
There are no function calls. There is no stack usage. All values are in
registers and fixed memory addresses.
Structure
=========
Each mode has its own loop routine. TX_START and TX_RUN use a single TX loop.
Code shared between different modes is implemented in macros and duplicated
within each mode's own loop.
At startup, the main routine sets up registers and memory, then falls through
to the idle loop.
The idle loop waits for a mode to be set, then jumps to that mode's start
label.
Code following the start label is executed only on a transition from IDLE. It
is at this point that the buffer statistics are reset.
Each mode's start code then falls through to its loop label.
The first step in each loop is to wait for an SGPIO interrupt and clear it,
which is implemented by the await_sgpio macro.
Then, the mode setting is loaded from memory. If the M4 has reset the mode to
idle, control jumps back to the idle loop after handling any cleanup needed.
Next, any SGPIO operations are carried out. For RX and TX, this begins with
calculating the buffer margin, and branching if there is a shortfall. Then
the pointer within the buffer is updated.
SGPIO reads and writes are implemented in 16-byte chunks. The four lowest
registers, r0-r3, are used to temporarily hold the data for each chunk. Data
is stored in-order in the buffer, but out-of-order in the SGPIO shadow
registers, due to the SGPIO architecture. A combination of single and
multiple load/stores is used to reorder the data in each chunk.
After completing SGPIO operations, counters are updated and the threshold
setting is checked. If the byte count has reached the threshold, the next
mode is set and a jump is made directly to the corresponding loop label.
Code at the start label of the new mode is not executed, so stats and
counters are maintained across a sequence of TX/RX/WAIT operations.
When a shortfall occurs, a branch is taken to a separate handler routine,
which branches back to the mode's normal loop when complete.
Most of the code for shortfall handling is common to RX and TX, and is
implemented in the handle_shortfall macro. This is primarily concerned with
updating statistics, but also handles switching back to IDLE mode if a
shortfall exceeds the configured limit.
There is a rollback mechanism implemented in the shortfall handling. This is
necessary because it is common for a harmless shortfall to occur during
shutdown, which produces misleading statistics. The code detects this case
when the mode is changed to IDLE whilst a shortfall is ongoing. If this
happens, statistics are rolled back to their values at the beginning of the
shortfall.
The backup of previous values is implemented in handle_shortfall when a new
shortfall is detected, and the rollback is implemented by the
checked_rollback routine. This routine is executed by the TX and RX loops
before returning to the idle loop.
Organisation
============
The rest of this file is organised as follows:
- Constant definitions
- Fixed register allocations
- Macros
- Ordering constraints
- Finally, the actual code!
*/
// Constants that point to registers we'll need to modify in the SGPIO block.
.equ SGPIO_SHADOW_REGISTERS_BASE, 0x40101100
.equ SGPIO_EXCHANGE_INTERRUPT_BASE, 0x40101F00
// Offsets into the interrupt control registers.
.equ INT_CLEAR, 0x30
.equ INT_STATUS, 0x2C
// Buffer that we're funneling data to/from.
.equ TARGET_DATA_BUFFER, 0x20008000
.equ TARGET_BUFFER_SIZE, 0x8000
.equ TARGET_BUFFER_MASK, 0x7fff
// Base address of the state structure.
.equ STATE_BASE, 0x20007000
// Offsets into the state structure.
.equ REQUESTED_MODE, 0x00
.equ ACTIVE_MODE, 0x04
.equ M0_COUNT, 0x08
.equ M4_COUNT, 0x0C
.equ NUM_SHORTFALLS, 0x10
.equ LONGEST_SHORTFALL, 0x14
.equ SHORTFALL_LIMIT, 0x18
.equ THRESHOLD, 0x1C
.equ NEXT_MODE, 0x20
.equ ERROR, 0x24
// Private variables stored after state.
.equ PREV_LONGEST_SHORTFALL, 0x28
// Operating modes.
.equ MODE_IDLE, 0
.equ MODE_WAIT, 1
.equ MODE_RX, 2
.equ MODE_TX_START, 3
.equ MODE_TX_RUN, 4
// Error codes.
.equ ERROR_NONE, 0
.equ ERROR_RX_TIMEOUT, 1
.equ ERROR_TX_TIMEOUT, 2
// Our slice chain is set up as follows (ascending data age; arrows are reversed for flow):
// L -> F -> K -> C -> J -> E -> I -> A
// Which has equivalent shadow register offsets:
// 44 -> 20 -> 40 -> 8 -> 36 -> 16 -> 32 -> 0
.equ SLICE0, 44
.equ SLICE1, 20
.equ SLICE2, 40
.equ SLICE3, 8
.equ SLICE4, 36
.equ SLICE5, 16
.equ SLICE6, 32
.equ SLICE7, 0
/* Allocations of single-use registers */
buf_size_minus_32 .req r14
state .req r13
buf_base .req r12
buf_mask .req r11
shortfall_length .req r10
hi_zero .req r9
sgpio_data .req r7
sgpio_int .req r6
count .req r5
buf_ptr .req r4
/* Macros */
.macro await_sgpio name
// Wait for, then clear, SGPIO exchange interrupt flag.
//
// Clobbers:
int_status .req r0
scratch .req r1
// The worst case timing is assumed to occur when reading the interrupt
// status register *just* misses the flag being set - so we include the
// cycles required to check it a second time.
//
// We also assume that we can spend a full 10 cycles doing an ldr from
// SGPIO the first time (2 for ldr, plus 8 for SGPIO-AHB bus latency),
// and still miss a flag that was set at the start of those 10 cycles.
//
// This latter asssumption is probably slightly pessimistic, since the
// sampling of the flag on the SGPIO side must occur some time after
// the ldr instruction begins executing on the M0. However, we avoid
// relying on any assumptions about the timing details of a read over
// the SGPIO to AHB bridge.
\name\()_int_wait:
// Spin on the exchange interrupt status, shifting the slice A flag to the carry flag.
ldr int_status, [sgpio_int, #INT_STATUS] // int_status = SGPIO_STATUS_1 // 10, twice
lsr scratch, int_status, #1 // scratch = int_status >> 1 // 1, twice
bcc \name\()_int_wait // if !carry: goto int_wait // 3, then 1
// Clear the interrupt pending bits that were set.
str int_status, [sgpio_int, #INT_CLEAR] // SGPIO_CLR_STATUS_1 = int_status // 8
.endm
.macro on_request label
// Check if a new mode change request was made, and if so jump to the given label.
mode .req r3
flag .req r2
ldr mode, [state, #REQUESTED_MODE] // mode = state.requested_mode // 2
lsr flag, mode, #16 // flag = mode >> 16 // 1
bne \label // if flag != 0: goto label // 1 thru, 3 taken
.endm
.macro update_buf_ptr
// Update the address of the buffer segment we want to write to / read from.
mov buf_ptr, buf_mask // buf_ptr = buf_mask // 1
and buf_ptr, count // buf_ptr &= count // 1
add buf_ptr, buf_base // buf_ptr += buf_base // 1
.endm
.macro update_counts
// Update counts after successful SGPIO operation.
// Update the byte count and store the new value.
add count, #32 // count += 32 // 1
str count, [state, #M0_COUNT] // state.m0_count = count // 2
// We didn't have a shortfall, so the current shortfall length is zero.
mov shortfall_length, hi_zero // shortfall_length = hi_zero // 1
.endm
.macro jump_next_mode name
// Jump to next mode if the byte count threshold has been reached.
//
// Clobbers:
threshold .req r0
new_mode .req r1
// Check count against threshold. If not a match, return to start of current loop.
ldr threshold, [state, #THRESHOLD] // threshold = state.threshold // 2
cmp count, threshold // if count != threshold: // 1
bne \name\()_loop // goto loop // 1 thru, 3 taken
// Otherwise, load and set new mode.
ldr new_mode, [state, #NEXT_MODE] // new_mode = state.next_mode // 2
str new_mode, [state, #ACTIVE_MODE] // state.active_mode = new_mode // 2
// Branch according to new mode.
cmp new_mode, #MODE_RX // if new_mode == RX: // 1
beq rx_loop // goto rx_loop // 1 thru, 3 taken
bgt tx_loop // elif new_mode > RX: goto tx_loop // 1 thru, 3 taken
cmp new_mode, #MODE_WAIT // if new_mode == WAIT: // 1
beq wait_loop // goto wait_loop // 1 thru, 3 taken
b idle // goto idle // 3
.endm
.macro handle_shortfall name
// Handle a shortfall.
//
// Clobbers:
length .req r0
num .req r1
prev .req r1
longest .req r1
limit .req r1
// Get current shortfall length from high register.
mov length, shortfall_length // length = shortfall_length // 1
// Is this a new shortfall?
cmp length, #0 // if length > 0: // 1
bgt \name\()_extend_shortfall // goto extend_shortfall // 1 thru, 3 taken
// If so, increase the shortfall count.
ldr num, [state, #NUM_SHORTFALLS] // num = state.num_shortfalls // 2
add num, #1 // num += 1 // 1
str num, [state, #NUM_SHORTFALLS] // state.num_shortfalls = num // 2
// Back up previous longest shortfall.
ldr prev, [state, #LONGEST_SHORTFALL] // prev = state.longest_shortfall // 2
str prev, [state, #PREV_LONGEST_SHORTFALL] // prev_longest_shortfall = prev // 2
\name\()_extend_shortfall:
// Extend the length of the current shortfall, and store back in high register.
add length, #32 // length += 32 // 1
mov shortfall_length, length // shortfall_length = length // 1
// Is this now the longest shortfall?
ldr longest, [state, #LONGEST_SHORTFALL] // longest = state.longest_shortfall // 2
cmp length, longest // if length <= longest: // 1
blt \name\()_loop // goto loop // 1 thru, 3 taken
str length, [state, #LONGEST_SHORTFALL] // state.longest_shortfall = length // 2
// Is this shortfall long enough to trigger a timeout?
ldr limit, [state, #SHORTFALL_LIMIT] // limit = state.shortfall_limit // 2
cmp limit, #0 // if limit == 0: // 1
beq \name\()_loop // goto loop // 1 thru, 3 taken
cmp length, limit // if length < limit: // 1
blt \name\()_loop // goto loop // 1 thru, 3 taken
// If so, reset mode to idle and return to idle loop, logging an error.
//
// Modes are mapped to errors as follows:
//
// MODE_RX (2) -> ERROR_RX_TIMEOUT (1)
// MODE_TX_RUN (4) -> ERROR_TX_TIMEOUT (2)
//
// As such, the error code can be obtained by shifting the mode right by 1 bit.
mode .req r3
error .req r2
ldr mode, [state, #ACTIVE_MODE] // mode = state.active_mode // 2
lsr error, mode, #1 // error = mode >> 1 // 1
str error, [state, #ERROR] // state.error = error // 2
mov mode, #MODE_IDLE // mode = MODE_IDLE // 1
str mode, [state, #ACTIVE_MODE] // state.active_mode = mode // 2
b idle // goto idle // 3
.endm
/*
Ordering constraints
====================
The following routines are in an unusual order, to preserve the ability to
use PC-relative conditional branches between them ("b<cond> label"). The
ordering has been chosen to ensure that all routines are close enough to each
other for the limited range of these instructions (256 bytes to +254 bytes).
The ordering of routines, and which others each needs to be able to reach, is
as follows:
Routine: Uses conditional branches to:
idle tx_loop, wait_loop
tx_zeros tx_loop
checked_rollback idle
tx_loop tx_zeros, checked_rollback, rx_loop, wait_loop
wait_loop rx_loop, tx_loop
rx_loop rx_shortfall, checked_rollback, tx_loop, wait_loop
rx_shortfall rx_loop
If any of these routines are reordered, or made longer, you may get an error
from the assembler saying that a branch is out of range.
*/
// Entry point. At this point, the libopencm3 startup code has set things up as
// normal; .data and .bss are initialised, the stack is set up, etc. However,
// we don't actually use any of that. All the code in this file would work
// fine if the M0 jumped straight to main at reset.
.global main
.thumb_func
main: // Cycle counts:
// Initialise registers used for constant values.
value .req r0
ldr sgpio_int, =SGPIO_EXCHANGE_INTERRUPT_BASE // sgpio_int = SGPIO_INT_BASE // 2
ldr sgpio_data, =SGPIO_SHADOW_REGISTERS_BASE // sgpio_data = SGPIO_REG_SS // 2
ldr value, =(TARGET_BUFFER_SIZE - 32) // value = TARGET_BUFFER_SIZE - 32 // 2
mov buf_size_minus_32, value // buf_size_minus_32 = value // 1
ldr value, =TARGET_DATA_BUFFER // value = TARGET_DATA_BUFFER // 2
mov buf_base, value // buf_base = value // 1
ldr value, =TARGET_BUFFER_MASK // value = TARGET_DATA_MASK // 2
mov buf_mask, value // buf_mask = value // 1
ldr value, =STATE_BASE // value = STATE_BASE // 2
mov state, value // state = value // 1
zero .req r0
mov zero, #0 // zero = 0 // 1
mov hi_zero, zero // hi_zero = zero // 1
// Initialise state.
str zero, [state, #REQUESTED_MODE] // state.requested_mode = zero // 2
str zero, [state, #ACTIVE_MODE] // state.active_mode = zero // 2
str zero, [state, #M0_COUNT] // state.m0_count = zero // 2
str zero, [state, #M4_COUNT] // state.m4_count = zero // 2
str zero, [state, #NUM_SHORTFALLS] // state.num_shortfalls = zero // 2
str zero, [state, #LONGEST_SHORTFALL] // state.longest_shortfall = zero // 2
str zero, [state, #SHORTFALL_LIMIT] // state.shortfall_limit = zero // 2
str zero, [state, #THRESHOLD] // state.threshold = zero // 2
str zero, [state, #NEXT_MODE] // state.next_mode = zero // 2
str zero, [state, #ERROR] // state.error = zero // 2
idle:
// Wait for a mode to be requested, then set up the new mode and acknowledge the request.
mode .req r3
flag .req r2
zero .req r0
// Read the requested mode and check flag to see if this is a new request. If not, ignore.
ldr mode, [state, #REQUESTED_MODE] // mode = state.requested_mode // 2
lsr flag, mode, #16 // flag = mode >> 16 // 1
beq idle // if flag == 0: goto idle // 1 thru, 3 taken
// Otherwise, this is a new request. The M4 is blocked at this point,
// waiting for us to clear the request flag. So we can safely write to
// all parts of the state.
// Set the new mode as both active & next.
uxth mode, mode // mode = mode & 0xFFFF // 1
str mode, [state, #ACTIVE_MODE] // state.active_mode = mode // 2
str mode, [state, #NEXT_MODE] // state.next_mode = mode // 2
// Don't reset counts on a transition to IDLE.
cmp mode, #MODE_IDLE // if mode == IDLE: // 1
beq ack_request // goto ack_request // 1 thru, 3 taken
// For all other transitions, reset counts.
mov zero, #0 // zero = 0 // 1
str zero, [state, #M0_COUNT] // state.m0_count = zero // 2
str zero, [state, #M4_COUNT] // state.m4_count = zero // 2
str zero, [state, #NUM_SHORTFALLS] // state.num_shortfalls = zero // 2
str zero, [state, #LONGEST_SHORTFALL] // state.longest_shortfall = zero // 2
str zero, [state, #THRESHOLD] // state.threshold = zero // 2
str zero, [state, #PREV_LONGEST_SHORTFALL] // prev_longest_shortfall = zero // 2
str zero, [state, #ERROR] // state.error = zero // 2
mov shortfall_length, zero // shortfall_length = zero // 1
mov count, zero // count = zero // 1
ack_request:
// Clear SGPIO interrupt flag, which the M4 set to get our attention.
str flag, [sgpio_int, #INT_CLEAR] // SGPIO_CLR_STATUS_1 = flag // 8
// Write back requested mode with the flag cleared to acknowledge the request.
str mode, [state, #REQUESTED_MODE] // state.requested_mode = mode // 2
// Dispatch to appropriate loop.
//
// This code is arranged such that the branch to rx_loop is the
// unconditional one - which is necessary since it's too far away to
// use a conditional branch instruction.
cmp mode, #MODE_WAIT // if mode < WAIT: // 1
blt idle // goto idle // 1 thru, 3 taken
beq wait_loop // elif mode == WAIT: goto wait_loop // 1 thru, 3 taken
cmp mode, #MODE_RX // if mode > RX: // 1
bgt tx_loop // goto tx_loop // 1 thru, 3 taken
b rx_loop // goto rx_loop // 3
tx_zeros:
// Write zeros to SGPIO.
mov zero, #0 // zero = 0 // 1
str zero, [sgpio_data, #SLICE0] // SGPIO_REG_SS[SLICE0] = zero // 8
str zero, [sgpio_data, #SLICE1] // SGPIO_REG_SS[SLICE1] = zero // 8
str zero, [sgpio_data, #SLICE2] // SGPIO_REG_SS[SLICE2] = zero // 8
str zero, [sgpio_data, #SLICE3] // SGPIO_REG_SS[SLICE3] = zero // 8
str zero, [sgpio_data, #SLICE4] // SGPIO_REG_SS[SLICE4] = zero // 8
str zero, [sgpio_data, #SLICE5] // SGPIO_REG_SS[SLICE5] = zero // 8
str zero, [sgpio_data, #SLICE6] // SGPIO_REG_SS[SLICE6] = zero // 8
str zero, [sgpio_data, #SLICE7] // SGPIO_REG_SS[SLICE7] = zero // 8
// If in TX start mode, don't count this as a shortfall.
ldr mode, [state, #ACTIVE_MODE] // mode = state.active_mode // 2
cmp mode, #MODE_TX_START // if mode == TX_START: // 1
beq tx_loop // goto tx_loop // 1 thru, 3 taken
// Run common shortfall handling and jump back to TX loop start.
handle_shortfall tx // handle_shortfall() // 24
checked_rollback:
// Checked rollback handler. This code is run when the M0 is in a TX or RX mode, and is
// placed back into IDLE mode by the M4. If there is an ongoing shortfall at this point,
// it is assumed to be a shutdown artifact and rolled back.
// If there is no ongoing shortfall, there's nothing to do - jump back to idle loop.
length .req r0
mov length, shortfall_length // length = shortfall_length // 1
cmp length, #0 // if length == 0: // 1
beq idle // goto idle // 3
// Otherwise, roll back the state to ignore the current shortfall, then jump to idle.
prev .req r0
ldr prev, [state, #PREV_LONGEST_SHORTFALL] // prev = prev_longest_shortfall // 2
str prev, [state, #LONGEST_SHORTFALL] // state.longest_shortfall = prev // 2
ldr prev, [state, #NUM_SHORTFALLS] // prev = num_shortfalls // 2
sub prev, #1 // prev -= 1 // 1
str prev, [state, #NUM_SHORTFALLS] // state.num_shortfalls = prev // 2
b idle // goto idle // 3
tx_loop:
// Wait for and clear SGPIO interrupt.
await_sgpio tx // await_sgpio() // 34
// Check if there is a mode change request.
// If so, we may need to roll back shortfall stats.
on_request checked_rollback // 4
// Check if there is enough data in the buffer.
//
// The number of bytes in the buffer is given by (m4_count - m0_count).
// We need 32 bytes available to proceed. So our margin, which we want
// to be positive or zero, is:
//
// buf_margin = m4_count - m0_count - 32
//
// If there is insufficient data, transmit zeros instead.
buf_margin .req r0
ldr buf_margin, [state, #M4_COUNT] // buf_margin = m4_count // 2
sub buf_margin, count // buf_margin -= count // 1
sub buf_margin, #32 // buf_margin -= 32 // 1
bmi tx_zeros // if buf_margin < 0: goto tx_zeros // 1 thru, 3 taken
// Update buffer pointer.
update_buf_ptr // update_buf_ptr() // 3
// At this point we know there is TX data available.
// Set active mode to TX_RUN (it might still be TX_START).
mov mode, #MODE_TX_RUN // mode = TX_RUN // 1
str mode, [state, #ACTIVE_MODE] // state.active_mode = mode // 2
// Write data to SGPIO.
ldm buf_ptr!, {r0-r3} // r0-r3 = buf_ptr[0:16]; buf_ptr += 16 // 5
str r0, [sgpio_data, #SLICE0] // SGPIO_REG_SS[SLICE0] = r0 // 8
str r1, [sgpio_data, #SLICE1] // SGPIO_REG_SS[SLICE1] = r1 // 8
str r2, [sgpio_data, #SLICE2] // SGPIO_REG_SS[SLICE2] = r2 // 8
str r3, [sgpio_data, #SLICE3] // SGPIO_REG_SS[SLICE3] = r3 // 8
ldm buf_ptr!, {r0-r3} // r0-r3 = buf_ptr[0:16]; buf_ptr += 16 // 5
str r0, [sgpio_data, #SLICE4] // SGPIO_REG_SS[SLICE4] = r0 // 8
str r1, [sgpio_data, #SLICE5] // SGPIO_REG_SS[SLICE5] = r1 // 8
str r2, [sgpio_data, #SLICE6] // SGPIO_REG_SS[SLICE6] = r2 // 8
str r3, [sgpio_data, #SLICE7] // SGPIO_REG_SS[SLICE7] = r3 // 8
// Update counts.
update_counts // update_counts() // 4
// Jump to next mode if threshold reached, or back to TX loop start.
jump_next_mode tx // jump_next_mode() // 13
wait_loop:
// Wait for and clear SGPIO interrupt.
await_sgpio wait // await_sgpio() // 34
// Check if there is a mode change request.
// If so, return to idle.
on_request idle // 4
// Update counts.
update_counts // update_counts() // 4
// Jump to next mode if threshold reached, or back to wait loop start.
jump_next_mode wait // jump_next_mode() // 15
rx_loop:
// Wait for and clear SGPIO interrupt.
await_sgpio rx // await_sgpio() // 34
// Check if there is a mode change request.
// If so, we may need to roll back shortfall stats.
on_request checked_rollback // 4
// Check if there is enough space in the buffer.
//
// The number of bytes in the buffer is given by (m0_count - m4_count).
// We need space for another 32 bytes to proceed. So our margin, which
// we want to be positive or zero, is:
//
// buf_margin = buf_size - (m0_count - state.m4_count) - 32
//
// which can be rearranged for efficiency as:
//
// buf_margin = m4_count + (buf_size - 32) - m0_count
//
// If there is insufficient space, jump to shortfall handling.
buf_margin .req r0
ldr buf_margin, [state, #M4_COUNT] // buf_margin = state.m4_count // 2
add buf_margin, buf_size_minus_32 // buf_margin += buf_size_minus_32 // 1
sub buf_margin, count // buf_margin -= count // 1
bmi rx_shortfall // if buf_margin < 0: goto rx_shortfall // 1 thru, 3 taken
// Update buffer pointer.
update_buf_ptr // update_buf_ptr() // 3
// Read data from SGPIO.
ldr r0, [sgpio_data, #SLICE0] // r0 = SGPIO_REG_SS[SLICE0] // 10
ldr r1, [sgpio_data, #SLICE1] // r1 = SGPIO_REG_SS[SLICE1] // 10
ldr r2, [sgpio_data, #SLICE2] // r2 = SGPIO_REG_SS[SLICE2] // 10
ldr r3, [sgpio_data, #SLICE3] // r3 = SGPIO_REG_SS[SLICE3] // 10
stm buf_ptr!, {r0-r3} // buf_ptr[0:16] = r0-r3; buf_ptr += 16 // 5
ldr r0, [sgpio_data, #SLICE4] // r0 = SGPIO_REG_SS[SLICE4] // 10
ldr r1, [sgpio_data, #SLICE5] // r1 = SGPIO_REG_SS[SLICE5] // 10
ldr r2, [sgpio_data, #SLICE6] // r2 = SGPIO_REG_SS[SLICE6] // 10
ldr r3, [sgpio_data, #SLICE7] // r3 = SGPIO_REG_SS[SLICE7] // 10
stm buf_ptr!, {r0-r3} // buf_ptr[0:16] = r0-r3; buf_ptr += 16 // 5
// Update counts.
update_counts // update_counts() // 4
// Jump to next mode if threshold reached, or back to RX loop start.
jump_next_mode rx // jump_next_mode() // 12
rx_shortfall:
// Run common shortfall handling and jump back to RX loop.
handle_shortfall rx // handle_shortfall() // 24
// The linker will put a literal pool here, so add a label for clearer objdump output:
constants:

View File

@ -0,0 +1,104 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_board_info.h"
#include <hackrf_core.h>
#include <rom_iap.h>
#include <usb_queue.h>
#include <libopencm3/lpc43xx/wwdt.h>
#include <stddef.h>
#include <string.h>
char version_string[] = VERSION_STRING;
usb_request_status_t usb_vendor_request_read_board_id(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
if (stage == USB_TRANSFER_STAGE_SETUP) {
endpoint->buffer[0] = BOARD_ID;
usb_transfer_schedule_block(endpoint->in, &endpoint->buffer, 1, NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
}
return USB_REQUEST_STATUS_OK;
}
usb_request_status_t usb_vendor_request_read_version_string(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
uint8_t length;
if (stage == USB_TRANSFER_STAGE_SETUP) {
length = (uint8_t)strlen(version_string);
usb_transfer_schedule_block(endpoint->in, version_string, length, NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
}
return USB_REQUEST_STATUS_OK;
}
usb_request_status_t usb_vendor_request_read_partid_serialno(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
uint8_t length;
read_partid_serialno_t read_partid_serialno;
iap_cmd_res_t iap_cmd_res;
if (stage == USB_TRANSFER_STAGE_SETUP)
{
/* Read IAP Part Number Identification */
iap_cmd_res.cmd_param.command_code = IAP_CMD_READ_PART_ID_NO;
iap_cmd_call(&iap_cmd_res);
if(iap_cmd_res.status_res.status_ret != CMD_SUCCESS)
return USB_REQUEST_STATUS_STALL;
read_partid_serialno.part_id[0] = iap_cmd_res.status_res.iap_result[0];
read_partid_serialno.part_id[1] = iap_cmd_res.status_res.iap_result[1];
/* Read IAP Serial Number Identification */
iap_cmd_res.cmd_param.command_code = IAP_CMD_READ_SERIAL_NO;
iap_cmd_call(&iap_cmd_res);
if(iap_cmd_res.status_res.status_ret != CMD_SUCCESS)
return USB_REQUEST_STATUS_STALL;
read_partid_serialno.serial_no[0] = iap_cmd_res.status_res.iap_result[0];
read_partid_serialno.serial_no[1] = iap_cmd_res.status_res.iap_result[1];
read_partid_serialno.serial_no[2] = iap_cmd_res.status_res.iap_result[2];
read_partid_serialno.serial_no[3] = iap_cmd_res.status_res.iap_result[3];
length = (uint8_t)sizeof(read_partid_serialno_t);
usb_transfer_schedule_block(endpoint->in, &read_partid_serialno, length,
NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
}
return USB_REQUEST_STATUS_OK;
}
usb_request_status_t usb_vendor_request_reset(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
if (stage == USB_TRANSFER_STAGE_SETUP) {
wwdt_reset(100000);
usb_transfer_schedule_ack(endpoint->in);
}
return USB_REQUEST_STATUS_OK;
}

View File

@ -0,0 +1,45 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_BOARD_INFO_H__
#define __USB_API_BOARD_INFO_H__
#include <stdint.h>
#include <usb_type.h>
#include <usb_request.h>
typedef struct {
uint32_t part_id[2];
uint32_t serial_no[4];
} read_partid_serialno_t;
usb_request_status_t usb_vendor_request_read_board_id(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_read_version_string(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_read_partid_serialno(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_reset(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
#endif /* end of include guard: __USB_API_BOARD_INFO_H__ */

View File

@ -0,0 +1,106 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_cpld.h"
#include <hackrf_core.h>
#include <cpld_jtag.h>
#include <cpld_xc2c.h>
#include <usb_queue.h>
#include "usb_endpoint.h"
#include <stddef.h>
#include <stdint.h>
#include <stdbool.h>
uint8_t cpld_xsvf_buffer[512];
volatile bool cpld_wait = false;
static void cpld_buffer_refilled(void* user_data, unsigned int length)
{
(void)user_data;
(void)length;
cpld_wait = false;
}
static void refill_cpld_buffer(void)
{
cpld_wait = true;
usb_transfer_schedule(
&usb_endpoint_bulk_out,
cpld_xsvf_buffer,
sizeof(cpld_xsvf_buffer),
cpld_buffer_refilled,
NULL
);
// Wait until transfer finishes
while (cpld_wait);
}
void cpld_update(void)
{
int error;
usb_queue_flush_endpoint(&usb_endpoint_bulk_in);
usb_queue_flush_endpoint(&usb_endpoint_bulk_out);
refill_cpld_buffer();
error = cpld_jtag_program(&jtag_cpld, sizeof(cpld_xsvf_buffer),
cpld_xsvf_buffer,
refill_cpld_buffer);
if(error == 0)
{
halt_and_flash(6000000);
}else
{
/* LED3 (Red) steady on error */
led_on(LED3);
while (1);
}
}
usb_request_status_t usb_vendor_request_cpld_checksum(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
static uint32_t cpld_crc;
uint8_t length;
if (stage == USB_TRANSFER_STAGE_SETUP)
{
cpld_jtag_take(&jtag_cpld);
const bool checksum_success = cpld_xc2c64a_jtag_checksum(&jtag_cpld, &cpld_hackrf_verify, &cpld_crc);
cpld_jtag_release(&jtag_cpld);
if(!checksum_success) {
return USB_REQUEST_STATUS_STALL;
}
length = (uint8_t)sizeof(cpld_crc);
usb_transfer_schedule_block(endpoint->in, &cpld_crc, length,
NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
}
return USB_REQUEST_STATUS_OK;
}

View File

@ -0,0 +1,36 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_CPLD_H__
#define __USB_API_CPLD_H__
#include <stdbool.h>
#include <usb_type.h>
#include <usb_request.h>
void cpld_update(void);
usb_request_status_t usb_vendor_request_cpld_checksum(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
#endif /* end of include guard: __USB_API_CPLD_H__ */

View File

@ -0,0 +1,60 @@
/*
* Copyright 2022 Great Scott Gadgets
*
* 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_m0_state.h"
#include <libopencm3/lpc43xx/sgpio.h>
#include <stddef.h>
#include <usb_request.h>
#include <usb_queue.h>
void m0_set_mode(enum m0_mode mode)
{
// Set requested mode and flag bit.
m0_state.requested_mode = M0_REQUEST_FLAG | mode;
// The M0 may be blocked waiting for the next SGPIO interrupt.
// In order to ensure that it sees our request, we need to set
// the interrupt flag here. The M0 will clear the flag again
// before acknowledging our request.
SGPIO_SET_STATUS_1 = (1 << SGPIO_SLICE_A);
// Wait for M0 to acknowledge by clearing the flag.
while (m0_state.requested_mode & M0_REQUEST_FLAG);
}
usb_request_status_t usb_vendor_request_get_m0_state(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
if( stage == USB_TRANSFER_STAGE_SETUP )
{
usb_transfer_schedule_block(
endpoint->in,
(void*) &m0_state,
sizeof(m0_state),
NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
return USB_REQUEST_STATUS_OK;
} else {
return USB_REQUEST_STATUS_OK;
}
}

View File

@ -0,0 +1,68 @@
/*
* Copyright 2022 Great Scott Gadgets
*
* 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 __M0_STATE_H__
#define __M0_STATE_H__
#include <stdint.h>
#include <usb_request.h>
#define M0_REQUEST_FLAG (1 << 16)
struct m0_state {
uint32_t requested_mode;
uint32_t active_mode;
uint32_t m0_count;
uint32_t m4_count;
uint32_t num_shortfalls;
uint32_t longest_shortfall;
uint32_t shortfall_limit;
uint32_t threshold;
uint32_t next_mode;
uint32_t error;
};
enum m0_mode {
M0_MODE_IDLE = 0,
M0_MODE_WAIT = 1,
M0_MODE_RX = 2,
M0_MODE_TX_START = 3,
M0_MODE_TX_RUN = 4,
};
enum m0_error {
M0_ERROR_NONE = 0,
M0_ERROR_RX_TIMEOUT = 1,
M0_ERROR_TX_TIMEOUT = 2,
};
/* Address of m0_state is set in ldscripts. If you change the name of this
* variable, it won't be where it needs to be in the processor's address space,
* unless you also adjust the ldscripts.
*/
extern volatile struct m0_state m0_state;
void m0_set_mode(enum m0_mode mode);
usb_request_status_t usb_vendor_request_get_m0_state(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
#endif/*__M0_STATE_H__*/

View File

@ -0,0 +1,153 @@
/*
* 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 <stddef.h>
#include <operacake.h>
#include <operacake_sctimer.h>
#include <sct.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) {
uint8_t addresses[8];
operacake_get_boards(addresses);
usb_transfer_schedule_block(endpoint->in, addresses, 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;
}
static unsigned char data[MAX_OPERACAKE_RANGES * 5];
usb_request_status_t usb_vendor_request_operacake_set_ranges(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
uint16_t i, freq_min, freq_max, num_ranges = 0;
uint8_t port;
if (stage == USB_TRANSFER_STAGE_SETUP) {
num_ranges = endpoint->setup.length / 5;
if((num_ranges == 0) || (num_ranges > MAX_OPERACAKE_RANGES)) {
return USB_REQUEST_STATUS_STALL;
}
operacake_clear_ranges();
usb_transfer_schedule_block(endpoint->out, &data,
endpoint->setup.length, NULL, NULL);
} else if (stage == USB_TRANSFER_STAGE_DATA) {
for(i=0; i<endpoint->setup.length; i+=5) {
freq_min = data[i] << 8 | data[i+1];
freq_max = data[i+2] << 8 | data[i+3];
port = data[i+4];
operacake_add_range(freq_min, freq_max, port);
}
usb_transfer_schedule_ack(endpoint->in);
}
return USB_REQUEST_STATUS_OK;
}
usb_request_status_t usb_vendor_request_operacake_gpio_test(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
uint16_t test_result;
uint8_t address = endpoint->setup.value & 0xFF;
if (stage == USB_TRANSFER_STAGE_SETUP) {
test_result = gpio_test(address);
endpoint->buffer[0] = test_result & 0xff;
endpoint->buffer[1] = test_result >> 8;
usb_transfer_schedule_block(endpoint->in, &endpoint->buffer, 2, NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
}
return USB_REQUEST_STATUS_OK;
}
usb_request_status_t usb_vendor_request_operacake_set_mode(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
uint8_t address, mode;
address = endpoint->setup.value & 0xFF;
mode = endpoint->setup.index & 0xFF;
if (stage == USB_TRANSFER_STAGE_SETUP) {
operacake_set_mode(address, mode);
usb_transfer_schedule_ack(endpoint->in);
}
return USB_REQUEST_STATUS_OK;
}
usb_request_status_t usb_vendor_request_operacake_get_mode(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
uint8_t address;
address = endpoint->setup.value & 0xFF;
if (stage == USB_TRANSFER_STAGE_SETUP) {
endpoint->buffer[0] = operacake_get_mode(address);
usb_transfer_schedule_block(endpoint->in, endpoint->buffer, 1, NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
}
return USB_REQUEST_STATUS_OK;
}
static struct operacake_dwell_times dwell_times[SCT_EVENT_COUNT];
usb_request_status_t usb_vendor_request_operacake_set_dwell_times(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
uint16_t count;
uint32_t dwell;
uint8_t port;
if (stage == USB_TRANSFER_STAGE_SETUP) {
count = endpoint->setup.length / 5;
if((count == 0) || (count > SCT_EVENT_COUNT)) {
return USB_REQUEST_STATUS_STALL;
}
usb_transfer_schedule_block(endpoint->out, &data,
endpoint->setup.length, NULL, NULL);
} else if (stage == USB_TRANSFER_STAGE_DATA) {
count = endpoint->setup.length / 5;
for(int i = 0; i < count; i++) {
dwell = data[(i*5)+0] | (data[(i*5)+1] << 8) | (data[(i*5)+2] << 16) | (data[(i*5)+3] << 24);
port = data[(i*5)+4];
dwell_times[i].dwell = dwell;
dwell_times[i].port = port;
}
operacake_sctimer_set_dwell_times(dwell_times, count);
usb_transfer_schedule_ack(endpoint->in);
}
return USB_REQUEST_STATUS_OK;
}

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.
*/
#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);
usb_request_status_t usb_vendor_request_operacake_set_ranges(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_operacake_gpio_test(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_operacake_set_mode(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_operacake_get_mode(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_operacake_set_dwell_times(
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,162 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_register.h"
#include <hackrf_core.h>
#include <usb_queue.h>
#include <max2837.h>
#include <rffc5071.h>
#include <stddef.h>
#include <stdint.h>
#include <hackrf_core.h>
usb_request_status_t usb_vendor_request_write_max2837(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
if( stage == USB_TRANSFER_STAGE_SETUP ) {
if( endpoint->setup.index < MAX2837_NUM_REGS ) {
if( endpoint->setup.value < MAX2837_DATA_REGS_MAX_VALUE ) {
max2837_reg_write(&max2837, endpoint->setup.index, endpoint->setup.value);
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
}
}
return USB_REQUEST_STATUS_STALL;
} else {
return USB_REQUEST_STATUS_OK;
}
}
usb_request_status_t usb_vendor_request_read_max2837(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
if( stage == USB_TRANSFER_STAGE_SETUP ) {
if( endpoint->setup.index < MAX2837_NUM_REGS ) {
const uint16_t value = max2837_reg_read(&max2837, endpoint->setup.index);
endpoint->buffer[0] = value & 0xff;
endpoint->buffer[1] = value >> 8;
usb_transfer_schedule_block(endpoint->in, &endpoint->buffer, 2,
NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
return USB_REQUEST_STATUS_OK;
}
return USB_REQUEST_STATUS_STALL;
} else {
return USB_REQUEST_STATUS_OK;
}
}
usb_request_status_t usb_vendor_request_write_si5351c(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
if( stage == USB_TRANSFER_STAGE_SETUP ) {
if( endpoint->setup.index < 256 ) {
if( endpoint->setup.value < 256 ) {
si5351c_write_single(&clock_gen, endpoint->setup.index, endpoint->setup.value);
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
}
}
return USB_REQUEST_STATUS_STALL;
} else {
return USB_REQUEST_STATUS_OK;
}
}
usb_request_status_t usb_vendor_request_read_si5351c(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
if( stage == USB_TRANSFER_STAGE_SETUP ) {
if( endpoint->setup.index < 256 ) {
const uint8_t value = si5351c_read_single(&clock_gen, endpoint->setup.index);
endpoint->buffer[0] = value;
usb_transfer_schedule_block(endpoint->in, &endpoint->buffer, 1,
NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
return USB_REQUEST_STATUS_OK;
}
return USB_REQUEST_STATUS_STALL;
} else {
return USB_REQUEST_STATUS_OK;
}
}
#ifndef RAD1O
usb_request_status_t usb_vendor_request_write_rffc5071(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
if( stage == USB_TRANSFER_STAGE_SETUP )
{
if( endpoint->setup.index < RFFC5071_NUM_REGS )
{
rffc5071_reg_write(&mixer, endpoint->setup.index, endpoint->setup.value);
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
}
return USB_REQUEST_STATUS_STALL;
} else {
return USB_REQUEST_STATUS_OK;
}
}
usb_request_status_t usb_vendor_request_read_rffc5071(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
uint16_t value;
if( stage == USB_TRANSFER_STAGE_SETUP )
{
if( endpoint->setup.index < RFFC5071_NUM_REGS )
{
value = rffc5071_reg_read(&mixer, endpoint->setup.index);
endpoint->buffer[0] = value & 0xff;
endpoint->buffer[1] = value >> 8;
usb_transfer_schedule_block(endpoint->in, &endpoint->buffer, 2,
NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
return USB_REQUEST_STATUS_OK;
}
return USB_REQUEST_STATUS_STALL;
} else {
return USB_REQUEST_STATUS_OK;
}
}
#endif
usb_request_status_t usb_vendor_request_set_clkout_enable(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
if (stage == USB_TRANSFER_STAGE_SETUP) {
si5351c_clkout_enable(&clock_gen, endpoint->setup.value);
usb_transfer_schedule_ack(endpoint->in);
}
return USB_REQUEST_STATUS_OK;
}

View File

@ -0,0 +1,58 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_REGISTER_H__
#define __USB_API_REGISTER_H__
#include <usb_type.h>
#include <usb_request.h>
usb_request_status_t usb_vendor_request_write_max2837(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
);
usb_request_status_t usb_vendor_request_read_max2837(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
);
usb_request_status_t usb_vendor_request_write_si5351c(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
);
usb_request_status_t usb_vendor_request_read_si5351c(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
);
usb_request_status_t usb_vendor_request_write_rffc5071(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
);
usb_request_status_t usb_vendor_request_read_rffc5071(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
);
usb_request_status_t usb_vendor_request_set_clkout_enable(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
);
#endif /* end of include guard: __USB_API_REGISTER_H__ */

View File

@ -0,0 +1,148 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_spiflash.h"
#include "usb_queue.h"
#include <stddef.h>
#include <hackrf_core.h>
#include <w25q80bv.h>
/* Buffer size == spi_flash.page_len */
uint8_t spiflash_buffer[256U];
usb_request_status_t usb_vendor_request_erase_spiflash(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
if (stage == USB_TRANSFER_STAGE_SETUP) {
spi_bus_start(spi_flash.bus, &ssp_config_w25q80bv);
w25q80bv_setup(&spi_flash);
/* only chip erase is implemented */
w25q80bv_chip_erase(&spi_flash);
usb_transfer_schedule_ack(endpoint->in);
}
return USB_REQUEST_STATUS_OK;
}
usb_request_status_t usb_vendor_request_write_spiflash(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
uint32_t addr = 0;
uint16_t len = 0;
if (stage == USB_TRANSFER_STAGE_SETUP) {
addr = (endpoint->setup.value << 16) | endpoint->setup.index;
len = endpoint->setup.length;
if ((len > spi_flash.page_len) || (addr > spi_flash.num_bytes)
|| ((addr + len) > spi_flash.num_bytes)) {
return USB_REQUEST_STATUS_STALL;
} else {
usb_transfer_schedule_block(endpoint->out, &spiflash_buffer[0], len,
NULL, NULL);
spi_bus_start(spi_flash.bus, &ssp_config_w25q80bv);
w25q80bv_setup(&spi_flash);
return USB_REQUEST_STATUS_OK;
}
} else if (stage == USB_TRANSFER_STAGE_DATA) {
addr = (endpoint->setup.value << 16) | endpoint->setup.index;
len = endpoint->setup.length;
/* This check is redundant but makes me feel better. */
if ((len > spi_flash.page_len) || (addr > spi_flash.num_bytes)
|| ((addr + len) > spi_flash.num_bytes)) {
return USB_REQUEST_STATUS_STALL;
} else {
w25q80bv_program(&spi_flash, addr, len, &spiflash_buffer[0]);
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
}
} else {
return USB_REQUEST_STATUS_OK;
}
}
usb_request_status_t usb_vendor_request_read_spiflash(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
uint32_t addr;
uint16_t len;
if (stage == USB_TRANSFER_STAGE_SETUP)
{
addr = (endpoint->setup.value << 16) | endpoint->setup.index;
len = endpoint->setup.length;
if ((len > spi_flash.page_len) || (addr > spi_flash.num_bytes)
|| ((addr + len) > spi_flash.num_bytes)) {
return USB_REQUEST_STATUS_STALL;
} else {
w25q80bv_read(&spi_flash, addr, len, &spiflash_buffer[0]);
usb_transfer_schedule_block(endpoint->in, &spiflash_buffer[0], len,
NULL, NULL);
return USB_REQUEST_STATUS_OK;
}
} else if (stage == USB_TRANSFER_STAGE_DATA)
{
addr = (endpoint->setup.value << 16) | endpoint->setup.index;
len = endpoint->setup.length;
/* This check is redundant but makes me feel better. */
if ((len > spi_flash.page_len) || (addr > spi_flash.num_bytes)
|| ((addr + len) > spi_flash.num_bytes))
{
return USB_REQUEST_STATUS_STALL;
} else
{
usb_transfer_schedule_ack(endpoint->out);
return USB_REQUEST_STATUS_OK;
}
} else
{
return USB_REQUEST_STATUS_OK;
}
}
usb_request_status_t usb_vendor_request_spiflash_status(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
uint8_t data[2];
if (stage == USB_TRANSFER_STAGE_SETUP) {
w25q80bv_get_full_status(&spi_flash, data);
usb_transfer_schedule_block(endpoint->in, &data, 2, NULL, NULL);
return USB_REQUEST_STATUS_OK;
} else if (stage == USB_TRANSFER_STAGE_DATA) {
usb_transfer_schedule_ack(endpoint->out);
return USB_REQUEST_STATUS_OK;
} else {
return USB_REQUEST_STATUS_OK;
}
}
usb_request_status_t usb_vendor_request_spiflash_clear_status(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
if (stage == USB_TRANSFER_STAGE_SETUP) {
w25q80bv_clear_status(&spi_flash);
usb_transfer_schedule_ack(endpoint->in);
}
return USB_REQUEST_STATUS_OK;
}

View File

@ -0,0 +1,40 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_SPIFLASH_H__
#define __USB_API_SPIFLASH_H__
#include <usb_type.h>
#include <usb_request.h>
usb_request_status_t usb_vendor_request_erase_spiflash(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_write_spiflash(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_read_spiflash(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_spiflash_status(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_spiflash_clear_status(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
#endif /* end of include guard: __USB_API_SPIFLASH_H__ */

View File

@ -0,0 +1,214 @@
/*
* 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 "usb_api_m0_state.h"
#include "tuning.h"
#include "usb_endpoint.h"
#include "streaming.h"
#include <libopencm3/lpc43xx/m4/nvic.h>
#define MIN(x,y) ((x)<(y)?(x):(y))
#define MAX(x,y) ((x)>(y)?(x):(y))
#define FREQ_GRANULARITY 1000000
#define MAX_RANGES 10
#define THROWAWAY_BUFFERS 2
static uint64_t sweep_freq;
static uint16_t frequencies[MAX_RANGES * 2];
static unsigned char data[9 + MAX_RANGES * 2 * sizeof(frequencies[0])];
static uint16_t num_ranges = 0;
static uint32_t dwell_blocks = 0;
static uint32_t step_width = 0;
static uint32_t offset = 0;
static enum sweep_style style = LINEAR;
/* Do this before starting sweep mode with request_transceiver_mode(). */
usb_request_status_t usb_vendor_request_init_sweep(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
uint32_t num_bytes;
int i;
if (stage == USB_TRANSFER_STAGE_SETUP) {
num_bytes = (endpoint->setup.index << 16) | endpoint->setup.value;
dwell_blocks = num_bytes / 0x4000;
if(1 > dwell_blocks) {
return USB_REQUEST_STATUS_STALL;
}
num_ranges = (endpoint->setup.length - 9) / (2 * sizeof(frequencies[0]));
if((1 > num_ranges) || (MAX_RANGES < num_ranges)) {
return USB_REQUEST_STATUS_STALL;
}
usb_transfer_schedule_block(endpoint->out, &data,
endpoint->setup.length, NULL, NULL);
} else if (stage == USB_TRANSFER_STAGE_DATA) {
step_width = ((uint32_t)(data[3]) << 24) | ((uint32_t)(data[2]) << 16)
| ((uint32_t)(data[1]) << 8) | data[0];
if(1 > step_width) {
return USB_REQUEST_STATUS_STALL;
}
offset = ((uint32_t)(data[7]) << 24) | ((uint32_t)(data[6]) << 16)
| ((uint32_t)(data[5]) << 8) | data[4];
style = data[8];
if(INTERLEAVED < style) {
return USB_REQUEST_STATUS_STALL;
}
for(i=0; i<(num_ranges*2); i++) {
frequencies[i] = ((uint16_t)(data[10+i*2]) << 8) + data[9+i*2];
}
sweep_freq = (uint64_t)frequencies[0] * FREQ_GRANULARITY;
set_freq(sweep_freq + offset);
usb_transfer_schedule_ack(endpoint->in);
}
return USB_REQUEST_STATUS_OK;
}
void sweep_bulk_transfer_complete(void *user_data, unsigned int bytes_transferred)
{
(void) user_data;
(void) bytes_transferred;
// For each buffer transferred, we need to bump the count by three buffers
// worth of data, to allow for the discarded buffers.
m0_state.m4_count += 3 * 0x4000;
}
void sweep_mode(uint32_t seq) {
// Sweep mode is implemented using timed M0 operations, as follows:
//
// 0. M4 initially puts the M0 into RX mode, with an m0_count threshold
// of 16K and a next mode of WAIT.
//
// 1. M4 spins until the M0 switches to WAIT mode.
//
// 2. M0 captures one 16K block of samples, and switches to WAIT mode.
//
// 3. M4 sees the mode change, advances the m0_count target by 32K, and
// sets next mode to RX.
//
// 4. M4 adds the sweep metadata at the start of the block and
// schedules a bulk transfer for the block.
//
// 5. M4 retunes - this takes about 760us worst-case, so should be
// complete before the M0 goes back to RX.
//
// 6. M4 spins until the M0 mode changes to RX, then advances the
// m0_count limit by 16K and sets the next mode to WAIT.
//
// 7. Process repeats from step 1.
unsigned int blocks_queued = 0;
unsigned int phase = 0;
bool odd = true;
uint16_t range = 0;
uint8_t *buffer;
transceiver_startup(TRANSCEIVER_MODE_RX_SWEEP);
// Set M0 to RX first buffer, then wait.
m0_state.threshold = 0x4000;
m0_state.next_mode = M0_MODE_WAIT;
baseband_streaming_enable(&sgpio_config);
while (transceiver_request.seq == seq) {
// Wait for M0 to finish receiving a buffer.
while (m0_state.active_mode != M0_MODE_WAIT)
if (transceiver_request.seq != seq)
goto end;
// Set M0 to switch back to RX after two more buffers.
m0_state.threshold += 0x8000;
m0_state.next_mode = M0_MODE_RX;
// Write metadata to buffer.
buffer = &usb_bulk_buffer[phase * 0x4000];
*buffer = 0x7f;
*(buffer+1) = 0x7f;
*(buffer+2) = sweep_freq & 0xff;
*(buffer+3) = (sweep_freq >> 8) & 0xff;
*(buffer+4) = (sweep_freq >> 16) & 0xff;
*(buffer+5) = (sweep_freq >> 24) & 0xff;
*(buffer+6) = (sweep_freq >> 32) & 0xff;
*(buffer+7) = (sweep_freq >> 40) & 0xff;
*(buffer+8) = (sweep_freq >> 48) & 0xff;
*(buffer+9) = (sweep_freq >> 56) & 0xff;
// Set up IN transfer of buffer.
usb_transfer_schedule_block(
&usb_endpoint_bulk_in,
buffer,
0x4000,
sweep_bulk_transfer_complete, NULL
);
// Use other buffer next time.
phase = (phase + 1) % 2;
if ( ++blocks_queued == dwell_blocks ) {
// Calculate next sweep frequency.
if(INTERLEAVED == style) {
if(!odd && ((sweep_freq + step_width) >= ((uint64_t)frequencies[1+range*2] * FREQ_GRANULARITY))) {
range = (range + 1) % num_ranges;
sweep_freq = (uint64_t)frequencies[range*2] * FREQ_GRANULARITY;
} else {
if(odd) {
sweep_freq += step_width/4;
} else {
sweep_freq += 3*step_width/4;
}
}
odd = !odd;
} else {
if((sweep_freq + step_width) >= ((uint64_t)frequencies[1+range*2] * FREQ_GRANULARITY)) {
range = (range + 1) % num_ranges;
sweep_freq = (uint64_t)frequencies[range*2] * FREQ_GRANULARITY;
} else {
sweep_freq += step_width;
}
}
// Retune to new frequency.
nvic_disable_irq(NVIC_USB0_IRQ);
set_freq(sweep_freq + offset);
nvic_enable_irq(NVIC_USB0_IRQ);
blocks_queued = 0;
}
// Wait for M0 to resume RX.
while (m0_state.active_mode != M0_MODE_RX)
if (transceiver_request.seq != seq)
goto end;
// Set M0 to switch back to WAIT after filling next buffer.
m0_state.threshold += 0x4000;
m0_state.next_mode = M0_MODE_WAIT;
}
end:
transceiver_shutdown();
}

View File

@ -0,0 +1,39 @@
/*
* 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_SWEEP_H__
#define __USB_API_SWEEP_H__
#include <stdbool.h>
#include <usb_type.h>
#include <usb_request.h>
enum sweep_style {
LINEAR = 0,
INTERLEAVED = 1,
};
usb_request_status_t usb_vendor_request_init_sweep(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
void sweep_mode(uint32_t seq);
#endif /* __USB_API_SWEEP_H__ */

View File

@ -0,0 +1,460 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_transceiver.h"
#include "hackrf_ui.h"
#include "operacake_sctimer.h"
#include <libopencm3/cm3/vector.h>
#include "usb_bulk_buffer.h"
#include "usb_api_m0_state.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>
#include <stddef.h>
#include <string.h>
#include "usb_endpoint.h"
#include "usb_api_sweep.h"
typedef struct {
uint32_t freq_mhz;
uint32_t freq_hz;
} set_freq_params_t;
set_freq_params_t set_freq_params;
struct set_freq_explicit_params {
uint64_t if_freq_hz; /* intermediate frequency */
uint64_t lo_freq_hz; /* front-end local oscillator frequency */
uint8_t path; /* image rejection filter path */
};
struct set_freq_explicit_params explicit_params;
typedef struct {
uint32_t freq_hz;
uint32_t divider;
} set_sample_r_params_t;
set_sample_r_params_t set_sample_r_params;
usb_request_status_t usb_vendor_request_set_baseband_filter_bandwidth(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
if( stage == USB_TRANSFER_STAGE_SETUP ) {
const uint32_t bandwidth = (endpoint->setup.index << 16) | endpoint->setup.value;
if( baseband_filter_bandwidth_set(bandwidth) ) {
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
}
return USB_REQUEST_STATUS_STALL;
} else {
return USB_REQUEST_STATUS_OK;
}
}
usb_request_status_t usb_vendor_request_set_freq(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage)
{
if (stage == USB_TRANSFER_STAGE_SETUP)
{
usb_transfer_schedule_block(endpoint->out, &set_freq_params, sizeof(set_freq_params_t),
NULL, NULL);
return USB_REQUEST_STATUS_OK;
} else if (stage == USB_TRANSFER_STAGE_DATA)
{
const uint64_t freq = set_freq_params.freq_mhz * 1000000ULL + set_freq_params.freq_hz;
if( set_freq(freq) )
{
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
}
return USB_REQUEST_STATUS_STALL;
} else
{
return USB_REQUEST_STATUS_OK;
}
}
usb_request_status_t usb_vendor_request_set_sample_rate_frac(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage)
{
if (stage == USB_TRANSFER_STAGE_SETUP)
{
usb_transfer_schedule_block(endpoint->out, &set_sample_r_params, sizeof(set_sample_r_params_t),
NULL, NULL);
return USB_REQUEST_STATUS_OK;
} else if (stage == USB_TRANSFER_STAGE_DATA)
{
if( sample_rate_frac_set(set_sample_r_params.freq_hz * 2, set_sample_r_params.divider ) )
{
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
}
return USB_REQUEST_STATUS_STALL;
} else
{
return USB_REQUEST_STATUS_OK;
}
}
usb_request_status_t usb_vendor_request_set_amp_enable(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
if (stage == USB_TRANSFER_STAGE_SETUP) {
switch (endpoint->setup.value) {
case 0:
rf_path_set_lna(&rf_path, 0);
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
case 1:
rf_path_set_lna(&rf_path, 1);
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_lna_gain(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage)
{
if( stage == USB_TRANSFER_STAGE_SETUP ) {
const uint8_t value = max2837_set_lna_gain(&max2837, endpoint->setup.index);
endpoint->buffer[0] = value;
if(value) hackrf_ui()->set_bb_lna_gain(endpoint->setup.index);
usb_transfer_schedule_block(endpoint->in, &endpoint->buffer, 1,
NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
return USB_REQUEST_STATUS_OK;
}
return USB_REQUEST_STATUS_OK;
}
usb_request_status_t usb_vendor_request_set_vga_gain(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
if( stage == USB_TRANSFER_STAGE_SETUP ) {
const uint8_t value = max2837_set_vga_gain(&max2837, endpoint->setup.index);
endpoint->buffer[0] = value;
if(value) hackrf_ui()->set_bb_vga_gain(endpoint->setup.index);
usb_transfer_schedule_block(endpoint->in, &endpoint->buffer, 1,
NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
return USB_REQUEST_STATUS_OK;
}
return USB_REQUEST_STATUS_OK;
}
usb_request_status_t usb_vendor_request_set_txvga_gain(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
if( stage == USB_TRANSFER_STAGE_SETUP ) {
const uint8_t value = max2837_set_txvga_gain(&max2837, endpoint->setup.index);
endpoint->buffer[0] = value;
if(value) hackrf_ui()->set_bb_tx_vga_gain(endpoint->setup.index);
usb_transfer_schedule_block(endpoint->in, &endpoint->buffer, 1,
NULL, NULL);
usb_transfer_schedule_ack(endpoint->out);
return USB_REQUEST_STATUS_OK;
}
return USB_REQUEST_STATUS_OK;
}
usb_request_status_t usb_vendor_request_set_antenna_enable(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage)
{
if (stage == USB_TRANSFER_STAGE_SETUP) {
switch (endpoint->setup.value) {
case 0:
rf_path_set_antenna(&rf_path, 0);
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
case 1:
rf_path_set_antenna(&rf_path, 1);
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_freq_explicit(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage)
{
if (stage == USB_TRANSFER_STAGE_SETUP) {
usb_transfer_schedule_block(endpoint->out, &explicit_params,
sizeof(struct set_freq_explicit_params), NULL, NULL);
return USB_REQUEST_STATUS_OK;
} else if (stage == USB_TRANSFER_STAGE_DATA) {
if (set_freq_explicit(explicit_params.if_freq_hz,
explicit_params.lo_freq_hz, explicit_params.path)) {
usb_transfer_schedule_ack(endpoint->in);
return USB_REQUEST_STATUS_OK;
}
return USB_REQUEST_STATUS_STALL;
} else {
return USB_REQUEST_STATUS_OK;
}
}
static volatile hw_sync_mode_t _hw_sync_mode = HW_SYNC_MODE_OFF;
static volatile uint32_t _tx_underrun_limit;
static volatile uint32_t _rx_overrun_limit;
void set_hw_sync_mode(const hw_sync_mode_t new_hw_sync_mode) {
_hw_sync_mode = new_hw_sync_mode;
}
volatile transceiver_request_t transceiver_request = {
.mode = TRANSCEIVER_MODE_OFF,
.seq = 0,
};
// Must be called from an atomic context (normally USB ISR)
void request_transceiver_mode(transceiver_mode_t mode)
{
usb_endpoint_flush(&usb_endpoint_bulk_in);
usb_endpoint_flush(&usb_endpoint_bulk_out);
transceiver_request.mode = mode;
transceiver_request.seq++;
}
void transceiver_shutdown(void)
{
baseband_streaming_disable(&sgpio_config);
operacake_sctimer_reset_state();
usb_endpoint_flush(&usb_endpoint_bulk_in);
usb_endpoint_flush(&usb_endpoint_bulk_out);
led_off(LED2);
led_off(LED3);
rf_path_set_direction(&rf_path, RF_PATH_DIRECTION_OFF);
m0_set_mode(M0_MODE_IDLE);
}
void transceiver_startup(const transceiver_mode_t mode) {
hackrf_ui()->set_transceiver_mode(mode);
switch (mode) {
case TRANSCEIVER_MODE_RX_SWEEP:
case TRANSCEIVER_MODE_RX:
led_off(LED3);
led_on(LED2);
rf_path_set_direction(&rf_path, RF_PATH_DIRECTION_RX);
m0_set_mode(M0_MODE_RX);
m0_state.shortfall_limit = _rx_overrun_limit;
break;
case TRANSCEIVER_MODE_TX:
led_off(LED2);
led_on(LED3);
rf_path_set_direction(&rf_path, RF_PATH_DIRECTION_TX);
m0_set_mode(M0_MODE_TX_START);
m0_state.shortfall_limit = _tx_underrun_limit;
break;
default:
break;
}
activate_best_clock_source();
hw_sync_enable(_hw_sync_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:
case TRANSCEIVER_MODE_RX_SWEEP:
case TRANSCEIVER_MODE_CPLD_UPDATE:
request_transceiver_mode(endpoint->setup.value);
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;
}
}
usb_request_status_t usb_vendor_request_set_tx_underrun_limit(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
if( stage == USB_TRANSFER_STAGE_SETUP ) {
uint32_t value = (endpoint->setup.index << 16) + endpoint->setup.value;
_tx_underrun_limit = value;
usb_transfer_schedule_ack(endpoint->in);
}
return USB_REQUEST_STATUS_OK;
}
usb_request_status_t usb_vendor_request_set_rx_overrun_limit(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
if( stage == USB_TRANSFER_STAGE_SETUP ) {
uint32_t value = (endpoint->setup.index << 16) + endpoint->setup.value;
_rx_overrun_limit = value;
usb_transfer_schedule_ack(endpoint->in);
}
return USB_REQUEST_STATUS_OK;
}
void transceiver_bulk_transfer_complete(void *user_data, unsigned int bytes_transferred)
{
(void) user_data;
m0_state.m4_count += bytes_transferred;
}
void rx_mode(uint32_t seq) {
unsigned int phase = 1;
transceiver_startup(TRANSCEIVER_MODE_RX);
baseband_streaming_enable(&sgpio_config);
while (transceiver_request.seq == seq) {
uint32_t m0_offset = m0_state.m0_count & USB_BULK_BUFFER_MASK;
// Set up IN transfer of buffer 0.
if (16384 <= m0_offset && 1 == phase) {
usb_transfer_schedule_block(
&usb_endpoint_bulk_in,
&usb_bulk_buffer[0x0000],
0x4000,
transceiver_bulk_transfer_complete,
NULL
);
phase = 0;
}
// Set up IN transfer of buffer 1.
if (16384 > m0_offset && 0 == phase) {
usb_transfer_schedule_block(
&usb_endpoint_bulk_in,
&usb_bulk_buffer[0x4000],
0x4000,
transceiver_bulk_transfer_complete,
NULL
);
phase = 1;
}
}
transceiver_shutdown();
}
void tx_mode(uint32_t seq) {
unsigned int phase = 0;
transceiver_startup(TRANSCEIVER_MODE_TX);
// Set up OUT transfer of buffer 0.
usb_transfer_schedule_block(
&usb_endpoint_bulk_out,
&usb_bulk_buffer[0x0000],
0x4000,
transceiver_bulk_transfer_complete,
NULL
);
// Enable streaming. The M0 is in TX_START mode, and will automatically
// send zeroes until the host fills buffer 0. Once that buffer is filled,
// the bulk transfer completion handler will increase the M4 count, and
// the M0 will switch to TX_RUN mode and transmit the first data.
baseband_streaming_enable(&sgpio_config);
while (transceiver_request.seq == seq) {
uint32_t m0_offset = m0_state.m0_count & USB_BULK_BUFFER_MASK;
// Set up OUT transfer of buffer 0.
if (16384 <= m0_offset && 1 == phase) {
usb_transfer_schedule_block(
&usb_endpoint_bulk_out,
&usb_bulk_buffer[0x0000],
0x4000,
transceiver_bulk_transfer_complete,
NULL
);
phase = 0;
}
// Set up OUT transfer of buffer 1.
if (16384 > m0_offset && 0 == phase) {
usb_transfer_schedule_block(
&usb_endpoint_bulk_out,
&usb_bulk_buffer[0x4000],
0x4000,
transceiver_bulk_transfer_complete,
NULL
);
phase = 1;
}
}
transceiver_shutdown();
}
void off_mode(uint32_t seq)
{
hackrf_ui()->set_transceiver_mode(TRANSCEIVER_MODE_OFF);
while (transceiver_request.seq == seq);
}

View File

@ -0,0 +1,78 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_TRANSCEIVER_H__
#define __USB_API_TRANSCEIVER_H__
#include <hackrf_core.h>
#include <usb_type.h>
#include <usb_request.h>
typedef struct {
transceiver_mode_t mode;
uint32_t seq;
} transceiver_request_t;
extern volatile transceiver_request_t transceiver_request;
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);
usb_request_status_t usb_vendor_request_set_baseband_filter_bandwidth(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_set_freq(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_set_sample_rate_frac(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_set_amp_enable(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_set_lna_gain(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_set_vga_gain(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_set_txvga_gain(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
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);
usb_request_status_t usb_vendor_request_set_tx_underrun_limit(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
usb_request_status_t usb_vendor_request_set_rx_overrun_limit(
usb_endpoint_t* const endpoint, const usb_transfer_stage_t stage);
void request_transceiver_mode(transceiver_mode_t mode);
void transceiver_startup(transceiver_mode_t mode);
void transceiver_shutdown(void);
void start_streaming_on_hw_sync();
void rx_mode(uint32_t seq);
void tx_mode(uint32_t seq);
void off_mode(uint32_t seq);
#endif/*__USB_API_TRANSCEIVER_H__*/

View File

@ -0,0 +1,40 @@
/*
* Copyright 2020 Mike Walters
*
* 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_ui.h"
#include <hackrf_core.h>
#include <hackrf_ui.h>
#include <usb_queue.h>
#include <stddef.h>
#include <stdint.h>
usb_request_status_t usb_vendor_request_set_ui_enable(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
) {
if (stage == USB_TRANSFER_STAGE_SETUP) {
hackrf_ui_set_enable(endpoint->setup.value);
usb_transfer_schedule_ack(endpoint->in);
}
return USB_REQUEST_STATUS_OK;
}

View File

@ -0,0 +1,33 @@
/*
* Copyright 2020 Mike Walters
*
* 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_UI_H__
#define __USB_API_UI_H__
#include <usb_type.h>
#include <usb_request.h>
usb_request_status_t usb_vendor_request_set_ui_enable(
usb_endpoint_t* const endpoint,
const usb_transfer_stage_t stage
);
#endif /* end of include guard: __USB_API_UI_H__ */

View File

@ -0,0 +1,38 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_BULK_BUFFER_H__
#define __USB_BULK_BUFFER_H__
#include <stdbool.h>
#include <stdint.h>
#define USB_BULK_BUFFER_SIZE 0x8000
#define USB_BULK_BUFFER_MASK 0x7FFF
/* Address of usb_bulk_buffer is set in ldscripts. If you change the name of this
* variable, it won't be where it needs to be in the processor's address space,
* unless you also adjust the ldscripts.
*/
extern uint8_t usb_bulk_buffer[USB_BULK_BUFFER_SIZE];
#endif/*__USB_BULK_BUFFER_H__*/

View File

@ -0,0 +1,313 @@
/*
* 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.
*/
#include <stdint.h>
#include "usb_type.h"
#include "usb_descriptor.h"
#define USB_VENDOR_ID (0x1D50)
#ifdef HACKRF_ONE
#define USB_PRODUCT_ID (0x6089)
#elif JAWBREAKER
#define USB_PRODUCT_ID (0x604B)
#elif RAD1O
#define USB_PRODUCT_ID (0xCC15)
#else
#define USB_PRODUCT_ID (0xFFFF)
#endif
#define USB_API_VERSION (0x0106)
#define USB_WORD(x) (x & 0xFF), ((x >> 8) & 0xFF)
#define USB_MAX_PACKET0 (64)
#define USB_MAX_PACKET_BULK_FS (64)
#define USB_MAX_PACKET_BULK_HS (512)
#define USB_BULK_IN_EP_ADDR (0x81)
#define USB_BULK_OUT_EP_ADDR (0x02)
#define USB_STRING_LANGID (0x0409)
uint8_t usb_descriptor_device[] = {
18, // bLength
USB_DESCRIPTOR_TYPE_DEVICE, // bDescriptorType
USB_WORD(0x0200), // bcdUSB
0x00, // bDeviceClass
0x00, // bDeviceSubClass
0x00, // bDeviceProtocol
USB_MAX_PACKET0, // bMaxPacketSize0
USB_WORD(USB_VENDOR_ID), // idVendor
USB_WORD(USB_PRODUCT_ID), // idProduct
USB_WORD(USB_API_VERSION), // bcdDevice
0x01, // iManufacturer
0x02, // iProduct
0x04, // iSerialNumber
0x01 // bNumConfigurations
};
uint8_t usb_descriptor_device_qualifier[] = {
10, // bLength
USB_DESCRIPTOR_TYPE_DEVICE_QUALIFIER, // bDescriptorType
USB_WORD(0x0200), // bcdUSB
0x00, // bDeviceClass
0x00, // bDeviceSubClass
0x00, // bDeviceProtocol
64, // bMaxPacketSize0
0x01, // bNumOtherSpeedConfigurations
0x00 // bReserved
};
uint8_t usb_descriptor_configuration_full_speed[] = {
9, // bLength
USB_DESCRIPTOR_TYPE_CONFIGURATION, // bDescriptorType
USB_WORD(32), // wTotalLength
0x01, // bNumInterfaces
0x01, // bConfigurationValue
0x03, // iConfiguration
0x80, // bmAttributes: USB-powered
250, // bMaxPower: 500mA
9, // bLength
USB_DESCRIPTOR_TYPE_INTERFACE, // bDescriptorType
0x00, // bInterfaceNumber
0x00, // bAlternateSetting
0x02, // bNumEndpoints
0xFF, // bInterfaceClass: vendor-specific
0xFF, // bInterfaceSubClass
0xFF, // bInterfaceProtocol: vendor-specific
0x00, // iInterface
7, // bLength
USB_DESCRIPTOR_TYPE_ENDPOINT, // bDescriptorType
USB_BULK_IN_EP_ADDR, // bEndpointAddress
0x02, // bmAttributes: BULK
USB_WORD(USB_MAX_PACKET_BULK_FS), // wMaxPacketSize
0x00, // bInterval: no NAK
7, // bLength
USB_DESCRIPTOR_TYPE_ENDPOINT, // bDescriptorType
USB_BULK_OUT_EP_ADDR, // bEndpointAddress
0x02, // bmAttributes: BULK
USB_WORD(USB_MAX_PACKET_BULK_FS), // wMaxPacketSize
0x00, // bInterval: no NAK
0, // TERMINATOR
};
uint8_t usb_descriptor_configuration_high_speed[] = {
9, // bLength
USB_DESCRIPTOR_TYPE_CONFIGURATION, // bDescriptorType
USB_WORD(32), // wTotalLength
0x01, // bNumInterfaces
0x01, // bConfigurationValue
0x03, // iConfiguration
0x80, // bmAttributes: USB-powered
250, // bMaxPower: 500mA
9, // bLength
USB_DESCRIPTOR_TYPE_INTERFACE, // bDescriptorType
0x00, // bInterfaceNumber
0x00, // bAlternateSetting
0x02, // bNumEndpoints
0xFF, // bInterfaceClass: vendor-specific
0xFF, // bInterfaceSubClass
0xFF, // bInterfaceProtocol: vendor-specific
0x00, // iInterface
7, // bLength
USB_DESCRIPTOR_TYPE_ENDPOINT, // bDescriptorType
USB_BULK_IN_EP_ADDR, // bEndpointAddress
0x02, // bmAttributes: BULK
USB_WORD(USB_MAX_PACKET_BULK_HS), // wMaxPacketSize
0x00, // bInterval: no NAK
7, // bLength
USB_DESCRIPTOR_TYPE_ENDPOINT, // bDescriptorType
USB_BULK_OUT_EP_ADDR, // bEndpointAddress
0x02, // bmAttributes: BULK
USB_WORD(USB_MAX_PACKET_BULK_HS), // wMaxPacketSize
0x00, // bInterval: no NAK
0, // TERMINATOR
};
uint8_t usb_descriptor_string_languages[] = {
0x04, // bLength
USB_DESCRIPTOR_TYPE_STRING, // bDescriptorType
USB_WORD(USB_STRING_LANGID), // wLANGID
};
uint8_t usb_descriptor_string_manufacturer[] = {
40, // bLength
USB_DESCRIPTOR_TYPE_STRING, // bDescriptorType
'G', 0x00,
'r', 0x00,
'e', 0x00,
'a', 0x00,
't', 0x00,
' ', 0x00,
'S', 0x00,
'c', 0x00,
'o', 0x00,
't', 0x00,
't', 0x00,
' ', 0x00,
'G', 0x00,
'a', 0x00,
'd', 0x00,
'g', 0x00,
'e', 0x00,
't', 0x00,
's', 0x00,
};
uint8_t usb_descriptor_string_product[] = {
#ifdef HACKRF_ONE
22, // bLength
USB_DESCRIPTOR_TYPE_STRING, // bDescriptorType
'H', 0x00,
'a', 0x00,
'c', 0x00,
'k', 0x00,
'R', 0x00,
'F', 0x00,
' ', 0x00,
'O', 0x00,
'n', 0x00,
'e', 0x00,
#elif JAWBREAKER
36, // bLength
USB_DESCRIPTOR_TYPE_STRING, // bDescriptorType
'H', 0x00,
'a', 0x00,
'c', 0x00,
'k', 0x00,
'R', 0x00,
'F', 0x00,
' ', 0x00,
'J', 0x00,
'a', 0x00,
'w', 0x00,
'b', 0x00,
'r', 0x00,
'e', 0x00,
'a', 0x00,
'k', 0x00,
'e', 0x00,
'r', 0x00,
#elif RAD1O
12, // bLength
USB_DESCRIPTOR_TYPE_STRING, // bDescriptorType
'r', 0x00,
'a', 0x00,
'd', 0x00,
'1', 0x00,
'o', 0x00,
#else
14, // bLength
USB_DESCRIPTOR_TYPE_STRING, // bDescriptorType
'H', 0x00,
'a', 0x00,
'c', 0x00,
'k', 0x00,
'R', 0x00,
'F', 0x00,
#endif
};
uint8_t usb_descriptor_string_config_description[] = {
24, // bLength
USB_DESCRIPTOR_TYPE_STRING, // bDescriptorType
'T', 0x00,
'r', 0x00,
'a', 0x00,
'n', 0x00,
's', 0x00,
'c', 0x00,
'e', 0x00,
'i', 0x00,
'v', 0x00,
'e', 0x00,
'r', 0x00,
};
#ifdef DFU_MODE
uint8_t usb_descriptor_string_serial_number[] = {
30, // bLength
USB_DESCRIPTOR_TYPE_STRING, // bDescriptorType
'R', 0x00,
'u', 0x00,
'n', 0x00,
'n', 0x00,
'i', 0x00,
'n', 0x00,
'g', 0x00,
'F', 0x00,
'r', 0x00,
'o', 0x00,
'm', 0x00,
'R', 0x00,
'A', 0x00,
'M', 0x00,
};
#else
uint8_t usb_descriptor_string_serial_number[USB_DESCRIPTOR_STRING_SERIAL_BUF_LEN];
#endif
uint8_t* usb_descriptor_strings[] = {
usb_descriptor_string_languages,
usb_descriptor_string_manufacturer,
usb_descriptor_string_product,
usb_descriptor_string_config_description,
usb_descriptor_string_serial_number,
0, // TERMINATOR
};
uint8_t wcid_string_descriptor[] = {
18, // bLength
USB_DESCRIPTOR_TYPE_STRING, // bDescriptorType
'M', 0x00,
'S', 0x00,
'F', 0x00,
'T', 0x00,
'1', 0x00,
'0', 0x00,
'0', 0x00,
USB_WCID_VENDOR_REQ, // vendor request code for further descriptor
0x00
};
uint8_t wcid_feature_descriptor[] = {
0x28, 0x00, 0x00, 0x00, // bLength
USB_WORD(0x0100), // WCID version
USB_WORD(0x0004), // WICD descriptor index
0x01, //bNumSections
0x00,0x00,0x00,0x00,0x00,0x00,0x00, //Reserved
0x00, //bInterfaceNumber
0x01, //Reserved
'W', 'I', 'N', 'U', 'S', 'B', 0x00,0x00, //Compatible ID, padded with zeros
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, //Sub-compatible ID
0x00,0x00,0x00,0x00,0x00,0x00 //Reserved
};

View File

@ -0,0 +1,40 @@
/*
* 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.
*/
#include <stdint.h>
extern uint8_t usb_descriptor_device[];
extern uint8_t usb_descriptor_device_qualifier[];
extern uint8_t usb_descriptor_configuration_full_speed[];
extern uint8_t usb_descriptor_configuration_high_speed[];
extern uint8_t usb_descriptor_string_languages[];
extern uint8_t usb_descriptor_string_manufacturer[];
extern uint8_t usb_descriptor_string_product[];
#define USB_DESCRIPTOR_STRING_SERIAL_LEN 32
#define USB_DESCRIPTOR_STRING_SERIAL_BUF_LEN (USB_DESCRIPTOR_STRING_SERIAL_LEN*2 + 2) /* UTF-16LE */
extern uint8_t usb_descriptor_string_serial_number[];
extern uint8_t* usb_descriptor_strings[];
#define USB_WCID_VENDOR_REQ 0x19
extern uint8_t wcid_string_descriptor[];
extern uint8_t wcid_feature_descriptor[];

View File

@ -0,0 +1,56 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_device.h"
#include <usb_type.h>
#include "usb_descriptor.h"
usb_configuration_t usb_configuration_high_speed = {
.number = 1,
.speed = USB_SPEED_HIGH,
.descriptor = usb_descriptor_configuration_high_speed,
};
usb_configuration_t usb_configuration_full_speed = {
.number = 1,
.speed = USB_SPEED_FULL,
.descriptor = usb_descriptor_configuration_full_speed,
};
usb_configuration_t* usb_configurations[] = {
&usb_configuration_high_speed,
&usb_configuration_full_speed,
0,
};
usb_device_t usb_device = {
.descriptor = usb_descriptor_device,
.descriptor_strings = usb_descriptor_strings,
.qualifier_descriptor = usb_descriptor_device_qualifier,
.configurations = &usb_configurations,
.configuration = 0,
.wcid_string_descriptor = wcid_string_descriptor,
.wcid_feature_descriptor = wcid_feature_descriptor,
};

View File

@ -0,0 +1,30 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_DEVICE_H__
#define __USB_DEVICE_H__
#include <usb_type.h>
extern usb_device_t usb_device;
#endif /* end of include guard: __USB_DEVICE_H__ */

View File

@ -0,0 +1,73 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_endpoint.h"
#include <usb_request.h>
#include "usb_device.h"
usb_endpoint_t usb_endpoint_control_out = {
.address = 0x00,
.device = &usb_device,
.in = &usb_endpoint_control_in,
.out = &usb_endpoint_control_out,
.setup_complete = usb_setup_complete,
.transfer_complete = usb_control_out_complete,
};
USB_DEFINE_QUEUE(usb_endpoint_control_out, 4);
usb_endpoint_t usb_endpoint_control_in = {
.address = 0x80,
.device = &usb_device,
.in = &usb_endpoint_control_in,
.out = &usb_endpoint_control_out,
.setup_complete = 0,
.transfer_complete = usb_control_in_complete,
};
static USB_DEFINE_QUEUE(usb_endpoint_control_in, 4);
// NOTE: Endpoint number for IN and OUT are different. I wish I had some
// evidence that having BULK IN and OUT on separate endpoint numbers was
// actually a good idea. Seems like everybody does it that way, but why?
usb_endpoint_t usb_endpoint_bulk_in = {
.address = 0x81,
.device = &usb_device,
.in = &usb_endpoint_bulk_in,
.out = 0,
.setup_complete = 0,
.transfer_complete = usb_queue_transfer_complete
};
static USB_DEFINE_QUEUE(usb_endpoint_bulk_in, 1);
usb_endpoint_t usb_endpoint_bulk_out = {
.address = 0x02,
.device = &usb_device,
.in = 0,
.out = &usb_endpoint_bulk_out,
.setup_complete = 0,
.transfer_complete = usb_queue_transfer_complete
};
static USB_DEFINE_QUEUE(usb_endpoint_bulk_out, 1);

View File

@ -0,0 +1,41 @@
/*
* Copyright 2012 Jared Boone
* Copyright 2013 Benjamin Vernoux
*
* 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_ENDPOINT_H__
#define __USB_ENDPOINT_H__
#include <usb_type.h>
#include <usb_queue.h>
extern usb_endpoint_t usb_endpoint_control_out;
extern USB_DECLARE_QUEUE(usb_endpoint_control_out);
extern usb_endpoint_t usb_endpoint_control_in;
extern USB_DECLARE_QUEUE(usb_endpoint_control_in);
extern usb_endpoint_t usb_endpoint_bulk_in;
extern USB_DECLARE_QUEUE(usb_endpoint_bulk_in);
extern usb_endpoint_t usb_endpoint_bulk_out;
extern USB_DECLARE_QUEUE(usb_endpoint_bulk_out);
#endif /* end of include guard: __USB_ENDPOINT_H__ */