Merge pull request #931 from miek/operacake-sctimer

Opera Cake SCTimer-based antenna switching
This commit is contained in:
Michael Ossmann
2021-10-14 18:21:26 -06:00
committed by GitHub
15 changed files with 2468 additions and 35 deletions

View File

@ -691,7 +691,7 @@ void cpu_clock_init(void)
CCU1_CLK_M4_LCD_CFG = 0;
CCU1_CLK_M4_QEI_CFG = 0;
CCU1_CLK_M4_RITIMER_CFG = 0;
CCU1_CLK_M4_SCT_CFG = 0;
// CCU1_CLK_M4_SCT_CFG = 0;
CCU1_CLK_M4_SDIO_CFG = 0;
CCU1_CLK_M4_SPIFI_CFG = 0;
CCU1_CLK_M4_TIMER0_CFG = 0;

View File

@ -20,6 +20,7 @@
*/
#include "operacake.h"
#include "operacake_sctimer.h"
#include "hackrf_core.h"
#include "gpio.h"
#include "gpio_lpc.h"
@ -71,17 +72,24 @@
#define OPERACAKE_ADDRESS_DEFAULT 0x18
#define OPERACAKE_ADDRESS_INVALID 0xFF
#define OPERACAKE_MAX_BOARDS 8
i2c_bus_t* const oc_bus = &i2c0;
uint8_t operacake_boards[8] = {
OPERACAKE_ADDRESS_INVALID,
OPERACAKE_ADDRESS_INVALID,
OPERACAKE_ADDRESS_INVALID,
OPERACAKE_ADDRESS_INVALID,
OPERACAKE_ADDRESS_INVALID,
OPERACAKE_ADDRESS_INVALID,
OPERACAKE_ADDRESS_INVALID,
OPERACAKE_ADDRESS_INVALID,
enum operacake_switching_mode {
MODE_MANUAL = 0,
MODE_FREQUENCY = 1,
MODE_TIME = 2,
};
struct operacake_state {
bool present;
enum operacake_switching_mode mode;
uint8_t PA;
uint8_t PB;
};
struct operacake_state operacake_boards[OPERACAKE_MAX_BOARDS];
bool allow_gpio_mode = true;
/* read single register */
@ -105,21 +113,76 @@ void operacake_write_reg(i2c_bus_t* const bus, uint8_t address, uint8_t reg, uin
}
uint8_t operacake_init(bool allow_gpio) {
uint8_t reg, addr, j = 0;
/* Find connected operacakes */
for(addr=0; addr<8; addr++) {
for (int addr = 0; addr < 8; addr++) {
operacake_write_reg(oc_bus, addr, OPERACAKE_REG_OUTPUT,
OPERACAKE_DEFAULT_OUTPUT);
operacake_write_reg(oc_bus, addr, OPERACAKE_REG_CONFIG,
OPERACAKE_CONFIG_ALL_OUTPUT);
reg = operacake_read_reg(oc_bus, addr, OPERACAKE_REG_CONFIG);
if(reg==OPERACAKE_CONFIG_ALL_OUTPUT)
operacake_boards[j++] = addr;
uint8_t reg = operacake_read_reg(oc_bus, addr, OPERACAKE_REG_CONFIG);
operacake_boards[addr].present = (reg == OPERACAKE_CONFIG_ALL_OUTPUT);
operacake_boards[addr].mode = MODE_MANUAL;
operacake_boards[addr].PA = OPERACAKE_PORT_A1;
operacake_boards[addr].PB = OPERACAKE_PORT_B1;
}
allow_gpio_mode = allow_gpio;
if (allow_gpio) {
operacake_sctimer_init();
}
return 0;
}
bool operacake_is_board_present(uint8_t address) {
if (address >= OPERACAKE_MAX_BOARDS)
return false;
return operacake_boards[address].present;
}
void operacake_get_boards(uint8_t *addresses) {
int count = 0;
for (int i = 0; i < OPERACAKE_MAX_BOARDS; i++) {
addresses[i] = OPERACAKE_ADDRESS_INVALID;
}
for (int i = 0; i < OPERACAKE_MAX_BOARDS; i++) {
if (operacake_is_board_present(i))
addresses[count++] = i;
}
}
void operacake_set_mode(uint8_t address, uint8_t mode) {
if (address >= OPERACAKE_MAX_BOARDS)
return;
operacake_boards[address].mode = mode;
if (mode == MODE_TIME) {
// Switch Opera Cake to pin-control mode
uint8_t config_pins = (uint8_t)~(OPERACAKE_PIN_OE(1) | OPERACAKE_PIN_LEDEN(1) | OPERACAKE_PIN_LEDEN2(1));
operacake_write_reg(oc_bus, address, OPERACAKE_REG_CONFIG, config_pins);
operacake_write_reg(oc_bus, address, OPERACAKE_REG_OUTPUT, OPERACAKE_GPIO_ENABLE | OPERACAKE_EN_LEDS);
} else {
operacake_write_reg(oc_bus, address, OPERACAKE_REG_CONFIG, OPERACAKE_CONFIG_ALL_OUTPUT);
operacake_set_ports(address, operacake_boards[address].PA, operacake_boards[address].PB);
}
// If any boards are in MODE_TIME, enable the sctimer events.
bool enable_sctimer = false;
for (int i = 0; i < OPERACAKE_MAX_BOARDS; i++) {
if (operacake_boards[i].mode == MODE_TIME)
enable_sctimer = true;
}
operacake_sctimer_enable(enable_sctimer);
}
uint8_t operacake_get_mode(uint8_t address) {
if (address >= OPERACAKE_MAX_BOARDS)
return 0;
return operacake_boards[address].mode;
}
uint8_t port_to_pins(uint8_t port) {
switch(port) {
case OPERACAKE_PA1:
@ -157,16 +220,24 @@ uint8_t operacake_set_ports(uint8_t address, uint8_t PA, uint8_t PB) {
|| ((PA > OPERACAKE_PA4) && (PB > OPERACAKE_PA4))) {
return 1;
}
if(PA > OPERACAKE_PA4) {
side = OPERACAKE_CROSSOVER;
} else {
side = OPERACAKE_SAMESIDE;
}
// Keep track of manual settings for when we switch in/out of time/frequency modes.
operacake_boards[address].PA = PA;
operacake_boards[address].PB = PB;
// Only apply register settings if the board is in manual mode.
if (operacake_boards[address].mode != MODE_MANUAL)
return 0;
pa = port_to_pins(PA);
pb = port_to_pins(PB);
reg = (OPERACAKE_GPIO_DISABLE | side
| pa | pb | OPERACAKE_EN_LEDS);
operacake_write_reg(oc_bus, address, OPERACAKE_REG_OUTPUT, reg);
@ -210,19 +281,26 @@ uint8_t operacake_set_range(uint32_t freq_mhz) {
if(range_idx == 0) {
return 1;
}
int i;
for(i=0; i<range_idx; i++) {
if((freq_mhz >= ranges[i].freq_min)
&& (freq_mhz <= ranges[i].freq_max)) {
int range;
for(range=0; range<range_idx; range++) {
if((freq_mhz >= ranges[range].freq_min)
&& (freq_mhz <= ranges[range].freq_max)) {
break;
}
}
if(i == current_range) {
if(range == current_range) {
return 1;
}
operacake_set_ports(operacake_boards[0], ranges[i].portA, ranges[i].portB);
current_range = i;
for (int i = 0; i < OPERACAKE_MAX_BOARDS; i++) {
if (operacake_is_board_present(i) && operacake_get_mode(i) == MODE_FREQUENCY) {
operacake_set_ports(i, ranges[range].portA, ranges[range].portB);
break;
}
}
current_range = range;
return 0;
}

View File

@ -42,10 +42,11 @@ extern "C"
#define MAX_OPERACAKE_RANGES 8
/* Up to 8 Operacake boards can be used with one HackRF */
extern uint8_t operacake_boards[8];
uint8_t operacake_init(bool allow_gpio);
bool operacake_is_board_present(uint8_t address);
void operacake_get_boards(uint8_t *addresses);
void operacake_set_mode(uint8_t address, uint8_t mode);
uint8_t operacake_get_mode(uint8_t address);
uint8_t operacake_set_ports(uint8_t address, uint8_t PA, uint8_t PB);
uint8_t operacake_add_range(uint16_t freq_min, uint16_t freq_max, uint8_t port);
uint8_t operacake_set_range(uint32_t freq_mhz);

View File

@ -0,0 +1,216 @@
/*
* Copyright 2018 Schuyler St. Leger
* Copyright 2021 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 "operacake_sctimer.h"
#include <hackrf_core.h>
#include <libopencm3/lpc43xx/sgpio.h>
#include <libopencm3/lpc43xx/rgu.h>
#include <libopencm3/lpc43xx/scu.h>
#include <libopencm3/lpc43xx/gima.h>
#include "sct.h"
#define U1CTRL_SET SCT_OUT14_SET
#define U1CTRL_CLR SCT_OUT14_CLR
#define U2CTRL0_SET SCT_OUT13_SET
#define U2CTRL0_CLR SCT_OUT13_CLR
#define U2CTRL1_SET SCT_OUT12_SET
#define U2CTRL1_CLR SCT_OUT12_CLR
#define U3CTRL0_SET SCT_OUT11_SET
#define U3CTRL0_CLR SCT_OUT11_CLR
#define U3CTRL1_SET SCT_OUT8_SET
#define U3CTRL1_CLR SCT_OUT8_CLR
static uint32_t default_output = 0;
/**
* Configure the SCTimer to rotate the antennas with the Operacake in phase with
* the sample clock. This will configure the SCTimer to output to the pins for
* GPIO control of the Operacake, however the Operacake must be configured for
* GPIO control. The timing is not set in this function.
*
* To trigger the antenna switching synchronously with the sample clock, the
* SGPIO is configured to output its clock (f=2 * sample clock) to the SCTimer.
*/
void operacake_sctimer_init() {
// We start by resetting the SCTimer
RESET_CTRL1 = RESET_CTRL1_SCT_RST;
// Delay to allow reset sigal to be processed
// The reset generator uses a 12MHz clock (IRC)
// The difference between this and the core clock (CCLK)
// determines this value (CCLK/IRC).
// The value used here is a bit shorter than would be required, since
// there are additional instructions that fill the time. If the duration of
// the actions from here to the first access to the SCTimer is changed, then
// this delay may need to be increased.
delay(8);
// Pin definitions for the HackRF
// U2CTRL0
scu_pinmux(P7_4, SCU_CONF_EPUN_DIS_PULLUP | SCU_CONF_EHS_FAST | SCU_CONF_FUNCTION1);
// U2CTRL1
scu_pinmux(P7_5, SCU_CONF_EPUN_DIS_PULLUP | SCU_CONF_EHS_FAST | SCU_CONF_FUNCTION1);
// U3CTRL0
scu_pinmux(P7_6, SCU_CONF_EPUN_DIS_PULLUP | SCU_CONF_EHS_FAST | SCU_CONF_FUNCTION1);
// U3CTRL1
scu_pinmux(P7_7, SCU_CONF_EPUN_DIS_PULLUP | SCU_CONF_EHS_FAST | SCU_CONF_FUNCTION1);
// U1CTRL
scu_pinmux(P7_0, SCU_CONF_EPUN_DIS_PULLUP | SCU_CONF_EHS_FAST | SCU_CONF_FUNCTION1);
// Configure the SGPIO to output the clock (f=2 * sample clock) on pin 12
SGPIO_OUT_MUX_CFG12 =
SGPIO_OUT_MUX_CFG_P_OUT_CFG(0x08) | // clkout output mode
SGPIO_OUT_MUX_CFG_P_OE_CFG(0); // gpio_oe
SGPIO_GPIO_OENREG |= BIT12;
// Use the GIMA to connect the SGPIO clock to the SCTimer
GIMA_CTIN_1_IN = 0x2 << 4; // Route SGPIO12 to SCTIN1
// We configure this register first, because the user manual says to
SCT_CONFIG |= SCT_CONFIG_UNIFY_32_BIT
| SCT_CONFIG_CLKMODE_PRESCALED_BUS_CLOCK
| SCT_CONFIG_CKSEL_RISING_EDGES_ON_INPUT_1;
// Halt the SCTimer to enable it to be configured
SCT_CTRL = SCT_CTRL_HALT_L(1);
// Prescaler - run at half the SGPIO clock (ie: at the sample clock)
SCT_CTRL |= SCT_CTRL_PRE_L(1);
// Default to state 0, events disabled
SCT_STATE = 0;
// Enable the SCTimer
SCT_CTRL &= ~SCT_CTRL_HALT_L(1);
}
static uint32_t operacake_sctimer_port_to_output(uint8_t port) {
int bit0 = (port >> 0) & 1;
int bit1 = (port >> 1) & 1;
int bit2 = (port >> 2) & 1;
return (bit0 << 11) | (bit0 << 13) |
(bit1 << 8) | (bit1 << 12) |
(((~bit2)&1) << 14);
}
void operacake_sctimer_enable(bool enable) {
SCT_CTRL = SCT_CTRL_HALT_L(1);
SCT_STATE = enable;
SCT_CTRL &= ~SCT_CTRL_HALT_L(1);
}
void operacake_sctimer_set_dwell_times(struct operacake_dwell_times *times, int n) {
SCT_CTRL = SCT_CTRL_HALT_L(1);
uint32_t counter = 0;
uint32_t bit0_set = 0, bit0_clr = 0, bit1_set = 0, bit1_clr = 0, bit2_set = 0, bit2_clr = 0;
for (int i = 0; i < n; i++) {
// Enable event i in state 1, set to match on match register i
SCT_EVn_STATE(i) = SCT_EVn_STATE_STATEMSK1(1);
SCT_EVn_CTRL(i) = SCT_EVn_CTRL_COMBMODE_MATCH | SCT_EVn_CTRL_MATCHSEL(i);
// Calculate the counter value to match on
counter += times[i].dwell;
// Wrapping from SCT_LIMIT seems to add an extra cycle,
// so we reduce the counter value for the first event.
if (i == 0)
counter -= 1;
SCT_MATCHn(i) = counter;
SCT_MATCHRELn(i) = counter;
// The match event selects the *next* port, so retreive that here.
int port;
if (i == n - 1) {
port = times[0].port;
} else {
port = times[i+1].port;
}
int bit0 = (port >> 0) & 1;
int bit1 = (port >> 1) & 1;
int bit2 = (port >> 2) & 1;
// Find bits to set/clear on event i
bit0_set |= SCT_OUTn_SETm( bit0, i);
bit0_clr |= SCT_OUTn_CLRm(~bit0, i);
bit1_set |= SCT_OUTn_SETm( bit1, i);
bit1_clr |= SCT_OUTn_CLRm(~bit1, i);
// (U1CTRL is inverted)
bit2_set |= SCT_OUTn_SETm(~bit2, i);
bit2_clr |= SCT_OUTn_CLRm( bit2, i);
}
// Apply event set/clear mappings
U2CTRL0_SET = bit0_set;
U2CTRL0_CLR = bit0_clr;
U3CTRL0_SET = bit0_set;
U3CTRL0_CLR = bit0_clr;
U2CTRL1_SET = bit1_set;
U2CTRL1_CLR = bit1_clr;
U3CTRL1_SET = bit1_set;
U3CTRL1_CLR = bit1_clr;
U1CTRL_SET = bit2_set;
U1CTRL_CLR = bit2_clr;
// Set output pins to select the first port in the list
default_output = operacake_sctimer_port_to_output(times[0].port);
SCT_OUTPUT = default_output;
// Reset counter on final event
SCT_LIMIT = (1 << (n-1));
SCT_CTRL &= ~SCT_CTRL_HALT_L(1);
}
void operacake_sctimer_stop() {
// Halt timer
SCT_CTRL |= SCT_CTRL_HALT_L(1);
}
/**
* This will reset the state of the SCTimer, but retains its configuration.
* This reset will return the selected antenna to 1 and samesided. This is
* called by set_transceiver_mode so the HackRF starts capturing with the
* same antenna selected each time.
*/
void operacake_sctimer_reset_state() {
SCT_CTRL |= SCT_CTRL_HALT_L(1);
// Clear the counter value
SCT_CTRL |= SCT_CTRL_CLRCTR_L(1);
// Reset to select the first port
SCT_OUTPUT = default_output;
SCT_CTRL &= ~SCT_CTRL_HALT_L(1);
}

View File

@ -0,0 +1,41 @@
/*
* Copyright 2016 Dominic Spill <dominicgs@gmail.com>
* Copyright 2018 Schuyler St. Leger
* Copyright 2021 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 __OPERACAKE_SCTIMER_H
#define __OPERACAKE_SCTIMER_H
#include <stdbool.h>
#include <stdint.h>
struct operacake_dwell_times {
uint32_t dwell;
uint8_t port;
};
void operacake_sctimer_init();
void operacake_sctimer_enable(bool enable);
void operacake_sctimer_set_dwell_times(struct operacake_dwell_times *times, int n);
void operacake_sctimer_stop();
void operacake_sctimer_reset_state();
#endif /* __OPERACAKE_SCTIMER_H */

1764
firmware/common/sct.h Normal file

File diff suppressed because it is too large Load Diff

View File

@ -1,6 +1,7 @@
/*
* Copyright 2012 Jared Boone <jared@sharebrained.com>
* Copyright 2013 Benjamin Vernoux <titanmkd@gmail.com>
* Copyright 2017 Schuyler St. Leger <schuyler.st.leger@gmail.com>
*
* This file is part of HackRF.
*
@ -159,7 +160,9 @@ void sgpio_configure(
const uint_fast8_t slice_count = config->slice_mode_multislice ? 8 : 1;
const uint_fast8_t clk_capture_mode = (direction == SGPIO_DIRECTION_TX) ? 0 : 0;
uint32_t slice_enable_mask = 0;
// Also enable slice D for clkout to the SCTimer
uint32_t slice_enable_mask = BIT3;
/* Configure Slice A, I, E, J, C, K, F, L (sgpio_slice_mode_multislice mode) */
for(uint_fast8_t i=0; i<slice_count; i++)
{

View File

@ -61,6 +61,7 @@ set(SRC_M4
"${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)

View File

@ -111,6 +111,9 @@ static usb_request_handler_fn vendor_request_handler[] = {
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,
};
static const uint32_t vendor_request_handler_count =

View File

@ -24,12 +24,16 @@
#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) {
usb_transfer_schedule_block(endpoint->in, operacake_boards, 8, NULL, NULL);
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;
@ -90,3 +94,59 @@ usb_request_status_t usb_vendor_request_operacake_gpio_test(
}
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

@ -37,4 +37,13 @@ usb_request_status_t usb_vendor_request_operacake_set_ranges(
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

@ -23,6 +23,8 @@
#include "usb_api_transceiver.h"
#include "hackrf_ui.h"
#include "operacake_sctimer.h"
#include <libopencm3/cm3/vector.h>
#include "usb_bulk_buffer.h"
@ -247,6 +249,7 @@ transceiver_mode_t transceiver_mode(void) {
void set_transceiver_mode(const transceiver_mode_t new_transceiver_mode) {
baseband_streaming_disable(&sgpio_config);
operacake_sctimer_reset_state();
usb_endpoint_flush(&usb_endpoint_bulk_in);
usb_endpoint_flush(&usb_endpoint_bulk_out);

View File

@ -37,6 +37,7 @@ typedef int bool;
#define MAX_FREQ_RANGES 8
#define INVALID_ADDRESS 0xFF
#define INVALID_MODE 0xFF
#define INVALID_PORT 0xFF
#define GPIO_TEST_DISABLED 0xFFFF
@ -46,9 +47,11 @@ static void usage() {
printf("\t-h, --help: this help\n");
printf("\t-d, --device <n>: specify a particular device by serial number\n");
printf("\t-o, --address <n>: specify a particular operacake by address [default: 0x00]\n");
printf("\t-m, --mode <mode>: specify switching mode [options: manual, frequency, time]\n");
printf("\t-a <n>: set port A connection\n");
printf("\t-b <n>: set port B connection\n");
printf("\t-f <min:max:port>: automatically assign <port> for range <min:max> in MHz\n");
printf("\t-t <port:dwell>: in time-switching mode, dwell on <port> for <dwell> samples. This argument can be repeated to specify a list of ports.\n");
printf("\t-l, --list: list available operacake boards\n");
printf("\t-g, --gpio_test: test GPIO functionality of an opera cake\n");
}
@ -56,6 +59,7 @@ static void usage() {
static struct option long_options[] = {
{ "device", no_argument, 0, 'd' },
{ "address", no_argument, 0, 'o' },
{ "mode", no_argument, 0, 'm' },
{ "list", no_argument, 0, 'l' },
{ "gpio_test", no_argument, 0, 'g' },
{ "help", no_argument, 0, 'h' },
@ -79,6 +83,17 @@ int parse_uint16(char* const s, uint16_t* const value) {
}
}
int parse_uint32(char* const s, uint32_t* const value) {
char* s_end = s;
const long long_value = strtol(s, &s_end, 10);
if( (s != s_end) && (*s_end == 0) ) {
*value = (uint32_t)long_value;
return HACKRF_SUCCESS;
} else {
return HACKRF_ERROR_INVALID_PARAM;
}
}
int parse_port(char* str, uint8_t* port) {
uint16_t tmp_port;
int result;
@ -139,10 +154,29 @@ int parse_range(char* s, hackrf_oc_range* range) {
return result;
}
int parse_dwell(char* s, hackrf_operacake_dwell_time* dwell_time) {
int result;
char port[16];
float dwell;
// Read dwell as a float here to support scientific notation (e.g: 1e6)
if (sscanf(s, "%15[^:]:%f", port, &dwell) == 2) {
result = parse_port(port, &dwell_time->port);
if (result != HACKRF_SUCCESS)
return result;
dwell_time->dwell = (uint32_t)dwell;
return HACKRF_SUCCESS;
}
return HACKRF_ERROR_INVALID_PARAM;
}
int main(int argc, char** argv) {
int opt;
const char* serial_number = NULL;
uint8_t operacake_address = INVALID_ADDRESS;
bool set_mode = false;
uint8_t mode;
uint8_t port_a = INVALID_PORT;
uint8_t port_b = INVALID_PORT;
bool set_ports = false;
@ -154,7 +188,9 @@ int main(int argc, char** argv) {
hackrf_device* device = NULL;
int option_index = 0;
hackrf_oc_range ranges[MAX_FREQ_RANGES];
hackrf_operacake_dwell_time dwell_times[HACKRF_OPERACAKE_MAX_DWELL_TIMES];
uint8_t range_idx = 0;
uint8_t dwell_idx = 0;
int result = hackrf_init();
if( result ) {
@ -162,7 +198,7 @@ int main(int argc, char** argv) {
return -1;
}
while( (opt = getopt_long(argc, argv, "d:o:a:b:lf:hg?", long_options, &option_index)) != EOF ) {
while( (opt = getopt_long(argc, argv, "d:o:a:m:b:lf:t:hg?", long_options, &option_index)) != EOF ) {
switch( opt ) {
case 'd':
serial_number = optarg;
@ -172,6 +208,24 @@ int main(int argc, char** argv) {
operacake_address = atoi(optarg);
break;
case 'm':
if (strcmp(optarg, "manual") == 0) {
mode = OPERACAKE_MODE_MANUAL;
set_mode = true;
} else if (strcmp(optarg, "frequency") == 0) {
mode = OPERACAKE_MODE_FREQUENCY;
set_mode = true;
} else if (strcmp(optarg, "time") == 0) {
mode = OPERACAKE_MODE_TIME;
set_mode = true;
} else {
fprintf(stderr,
"argument error: mode must be one of [manual, frequency, time].\n");
usage();
return EXIT_FAILURE;
}
break;
case 'f':
if(MAX_FREQ_RANGES == range_idx) {
fprintf(stderr,
@ -201,6 +255,22 @@ int main(int argc, char** argv) {
range_idx++;
break;
case 't':
if(HACKRF_OPERACAKE_MAX_DWELL_TIMES == dwell_idx) {
fprintf(stderr,
"argument error: specify a maximum of %u dwell times.\n",
HACKRF_OPERACAKE_MAX_DWELL_TIMES);
usage();
return EXIT_FAILURE;
}
result = parse_dwell(optarg, &dwell_times[dwell_idx]);
if (result != HACKRF_SUCCESS) {
fprintf(stderr, "failed to parse dwell time\n");
return EXIT_FAILURE;
}
dwell_idx++;
break;
case 'a':
result = parse_port(optarg, &port_a);
if (result != HACKRF_SUCCESS) {
@ -239,13 +309,13 @@ int main(int argc, char** argv) {
}
}
if(!(list || set_ports || range_idx || gpio_test)) {
fprintf(stderr, "Specify either list, address, or GPIO test option.\n");
if(!(list || set_mode || set_ports || range_idx || gpio_test)) {
fprintf(stderr, "Specify either list, mode, address, or GPIO test option.\n");
usage();
return EXIT_FAILURE;
}
if((set_ports || gpio_test) && (operacake_address == INVALID_ADDRESS)) {
if((set_mode || set_ports || gpio_test) && (operacake_address == INVALID_ADDRESS)) {
fprintf(stderr, "An address is required.\n");
usage();
return EXIT_FAILURE;
@ -258,6 +328,15 @@ int main(int argc, char** argv) {
return EXIT_FAILURE;
}
if (set_mode) {
result = hackrf_set_operacake_mode(device, operacake_address, mode);
if (result != HACKRF_SUCCESS) {
fprintf(stderr, "hackrf_set_operacake_mode() failed: %s (%d)\n",
hackrf_error_name(result), result);
return EXIT_FAILURE;
}
}
if(list) {
result = hackrf_get_operacake_boards(device, operacakes);
if (result != HACKRF_SUCCESS) {
@ -269,6 +348,18 @@ int main(int argc, char** argv) {
for(i=0; i<8; i++) {
if(operacakes[i] != HACKRF_OPERACAKE_ADDRESS_INVALID) {
printf("\n\tAddress: %d", operacakes[i]);
enum operacake_switching_mode mode;
hackrf_get_operacake_mode(device, i, &mode);
printf("\tSwitching mode: ");
if (mode == OPERACAKE_MODE_MANUAL) {
printf("manual\n");
} else if (mode == OPERACAKE_MODE_FREQUENCY) {
printf("frequency\n");
} else if (mode == OPERACAKE_MODE_TIME) {
printf("time\n");
} else {
printf("unknown\n");
}
operacake_count++;
}
}
@ -373,6 +464,14 @@ int main(int argc, char** argv) {
}
}
if(dwell_idx) {
result = hackrf_set_operacake_dwell_times(device, dwell_times, dwell_idx);
if( result ) {
printf("hackrf_set_operacake_dwell_times() failed: %s (%d)\n", hackrf_error_name(result), result);
return -1;
}
}
result = hackrf_close(device);
if( result ) {
printf("hackrf_close() failed: %s (%d)\n", hackrf_error_name(result), result);

View File

@ -89,6 +89,9 @@ typedef enum {
HACKRF_VENDOR_REQUEST_OPERACAKE_GPIO_TEST = 35,
HACKRF_VENDOR_REQUEST_CPLD_CHECKSUM = 36,
HACKRF_VENDOR_REQUEST_UI_ENABLE = 37,
HACKRF_VENDOR_REQUEST_OPERACAKE_SET_MODE = 38,
HACKRF_VENDOR_REQUEST_OPERACAKE_GET_MODE = 39,
HACKRF_VENDOR_REQUEST_OPERACAKE_SET_DWELL_TIMES = 40,
} hackrf_vendor_request;
#define USB_CONFIG_STANDARD 0x1
@ -2090,6 +2093,10 @@ int ADDCALL hackrf_init_sweep(hackrf_device* device,
}
}
bool hackrf_operacake_valid_address(uint8_t address) {
return address < HACKRF_OPERACAKE_MAX_BOARDS;
}
/**
* Retrieve list of Opera Cake board addresses
* @param[in] device
@ -2121,6 +2128,82 @@ int ADDCALL hackrf_get_operacake_boards(hackrf_device* device, uint8_t* boards)
}
}
/**
* Set Opera Cake switching mode.
* @param[in] device
* @param[in] address Opera Cake address.
* @param[in] mode Switching mode.
* @return @ref HACKRF_SUCCESS
* @return @ref HACKRF_ERROR_LIBUSB
*/
int ADDCALL hackrf_set_operacake_mode(hackrf_device* device, uint8_t address, enum operacake_switching_mode mode)
{
USB_API_REQUIRED(device, 0x0105)
if (!hackrf_operacake_valid_address(address)) {
return HACKRF_ERROR_INVALID_PARAM;
}
int result;
result = libusb_control_transfer(
device->usb_device,
LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE,
HACKRF_VENDOR_REQUEST_OPERACAKE_SET_MODE,
address,
(uint8_t)mode,
NULL,
0,
0
);
if (result != 0)
{
last_libusb_error = result;
return HACKRF_ERROR_LIBUSB;
} else {
return HACKRF_SUCCESS;
}
}
/**
* Get Opera Cake switching mode.
* @param[in] device
* @param[in] address Opera Cake address.
* @param[out] mode Switching mode.
* @return @ref HACKRF_SUCCESS
* @return @ref HACKRF_ERROR_LIBUSB
*/
int ADDCALL hackrf_get_operacake_mode(hackrf_device* device, uint8_t address, enum operacake_switching_mode *mode)
{
USB_API_REQUIRED(device, 0x0105)
if (!hackrf_operacake_valid_address(address)) {
return HACKRF_ERROR_INVALID_PARAM;
}
int result;
uint8_t buf;
result = libusb_control_transfer(
device->usb_device,
LIBUSB_ENDPOINT_IN | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE,
HACKRF_VENDOR_REQUEST_OPERACAKE_GET_MODE,
address,
0,
&buf,
1,
0
);
if (result < 1)
{
last_libusb_error = result;
return HACKRF_ERROR_LIBUSB;
} else {
*mode = buf;
return HACKRF_SUCCESS;
}
}
/* Set Operacake ports */
int ADDCALL hackrf_set_operacake_ports(hackrf_device* device,
uint8_t address,
@ -2128,6 +2211,11 @@ int ADDCALL hackrf_set_operacake_ports(hackrf_device* device,
uint8_t port_b)
{
USB_API_REQUIRED(device, 0x0102)
if (!hackrf_operacake_valid_address(address)) {
return HACKRF_ERROR_INVALID_PARAM;
}
int result;
/* Error checking */
if((port_a > OPERACAKE_PB4) || (port_b > OPERACAKE_PB4)) {
@ -2181,8 +2269,8 @@ int ADDCALL hackrf_reset(hackrf_device* device) {
int ADDCALL hackrf_set_operacake_ranges(hackrf_device* device, uint8_t* ranges, uint8_t len_ranges)
{
USB_API_REQUIRED(device, 0x0103)
int result;
int result;
result = libusb_control_transfer(
device->usb_device,
LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE,
@ -2202,6 +2290,43 @@ int ADDCALL hackrf_set_operacake_ranges(hackrf_device* device, uint8_t* ranges,
}
}
#define DWELL_TIME_SIZE 5
static uint8_t dwell_data[DWELL_TIME_SIZE*HACKRF_OPERACAKE_MAX_DWELL_TIMES];
int ADDCALL hackrf_set_operacake_dwell_times(hackrf_device* device, hackrf_operacake_dwell_time *dwell_times, uint8_t count)
{
USB_API_REQUIRED(device, 0x0105)
if (count > HACKRF_OPERACAKE_MAX_DWELL_TIMES) {
return HACKRF_ERROR_INVALID_PARAM;
}
int i;
for (i = 0; i < count; i++) {
*(uint32_t*)&dwell_data[i*DWELL_TIME_SIZE] = TO_LE(dwell_times[i].dwell);
dwell_data[(i*DWELL_TIME_SIZE)+4] = dwell_times[i].port;
}
int data_len = count * DWELL_TIME_SIZE;
int result;
result = libusb_control_transfer(
device->usb_device,
LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE,
HACKRF_VENDOR_REQUEST_OPERACAKE_SET_DWELL_TIMES,
0,
0,
dwell_data,
data_len,
0
);
if (result < data_len) {
last_libusb_error = result;
return HACKRF_ERROR_LIBUSB;
} else {
return HACKRF_SUCCESS;
}
}
int ADDCALL hackrf_set_clkout_enable(hackrf_device* device, const uint8_t value)
{
USB_API_REQUIRED(device, 0x0103)
@ -2230,6 +2355,11 @@ int ADDCALL hackrf_operacake_gpio_test(hackrf_device* device, const uint8_t addr
uint16_t* test_result)
{
USB_API_REQUIRED(device, 0x0103)
if (!hackrf_operacake_valid_address(address)) {
return HACKRF_ERROR_INVALID_PARAM;
}
int result;
result = libusb_control_transfer(
device->usb_device,

View File

@ -51,6 +51,8 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
#define BYTES_PER_BLOCK 16384
#define MAX_SWEEP_RANGES 10
#define HACKRF_OPERACAKE_ADDRESS_INVALID 0xFF
#define HACKRF_OPERACAKE_MAX_BOARDS 8
#define HACKRF_OPERACAKE_MAX_DWELL_TIMES 16
enum hackrf_error {
HACKRF_SUCCESS = 0,
@ -101,6 +103,21 @@ enum operacake_ports {
OPERACAKE_PB4 = 7,
};
enum operacake_switching_mode {
/**
* Port connections are set manually using @ref hackrf_set_operacake_ports.
*/
OPERACAKE_MODE_MANUAL,
/**
* Port connections are switched automatically when the frequency is changed. Frequency ranges can be set using @ref hackrf_set_operacake_ranges.
*/
OPERACAKE_MODE_FREQUENCY,
/**
* Port connections are switched automatically over time.
*/
OPERACAKE_MODE_TIME,
};
enum sweep_style {
LINEAR = 0,
INTERLEAVED = 1,
@ -122,6 +139,11 @@ typedef struct {
uint32_t serial_no[4];
} read_partid_serialno_t;
typedef struct {
uint32_t dwell;
uint8_t port;
} hackrf_operacake_dwell_time;
struct hackrf_device_list {
char **serial_numbers;
@ -238,10 +260,13 @@ extern ADDAPI int ADDCALL hackrf_init_sweep(hackrf_device* device,
/* Operacake functions */
extern ADDAPI int ADDCALL hackrf_get_operacake_boards(hackrf_device* device, uint8_t* boards);
extern ADDAPI int ADDCALL hackrf_set_operacake_mode(hackrf_device* device, uint8_t address, enum operacake_switching_mode mode);
extern ADDAPI int ADDCALL hackrf_get_operacake_mode(hackrf_device* device, uint8_t address, enum operacake_switching_mode *mode);
extern ADDAPI int ADDCALL hackrf_set_operacake_ports(hackrf_device* device,
uint8_t address,
uint8_t port_a,
uint8_t port_b);
extern ADDAPI int ADDCALL hackrf_set_operacake_dwell_times(hackrf_device* device, hackrf_operacake_dwell_time *dwell_times, uint8_t count);
extern ADDAPI int ADDCALL hackrf_reset(hackrf_device* device);