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,39 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "debounce.hpp"
#include "utility.hpp"
bool Debounce::feed(const uint8_t bit) {
history_ = (history_ << 1) | (bit & 1);
if( history_ == 0b00001111 ) {
state_ = 1;
return true;
}
if( history_ == 0b11110000 ) {
state_ = 0;
return true;
}
return false;
}

View File

@ -0,0 +1,40 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __DEBOUNCE_H__
#define __DEBOUNCE_H__
#include <cstdint>
class Debounce {
public:
bool feed(const uint8_t bit);
uint8_t state() const {
return state_;
}
private:
uint8_t history_ { 0 };
uint8_t state_ { 0 };
};
#endif/*__DEBOUNCE_H__*/

View File

@ -0,0 +1,55 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "encoder.hpp"
#include "utility.hpp"
static const int8_t transition_map[] = {
0, // 0000: noop
0, // 0001: start
0, // 0010: start
0, // 0011: rate
1, // 0100: end
0, // 0101: noop
0, // 0110: rate
-1, // 0111: end
-1, // 1000: end
0, // 1001: rate
0, // 1010: noop
1, // 1011: end
0, // 1100: rate
0, // 1101: start
0, // 1110: start
0, // 1111: noop
};
int_fast8_t Encoder::update(
const uint_fast8_t phase_0,
const uint_fast8_t phase_1
) {
state <<= 1;
state |= phase_0;
state <<= 1;
state |= phase_1;
return transition_map[state & 0xf];
}

View File

@ -0,0 +1,38 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __ENCODER_H__
#define __ENCODER_H__
#include <cstdint>
class Encoder {
public:
int_fast8_t update(
const uint_fast8_t phase_0,
const uint_fast8_t phase_1
);
private:
uint_fast8_t state { 0 };
};
#endif/*__ENCODER_H__*/

View File

@ -0,0 +1,294 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "max2837.hpp"
#include "hackrf_hal.hpp"
#include "hackrf_gpio.hpp"
using namespace hackrf::one;
#include "ch.h"
#include "hal.h"
#include <algorithm>
namespace max2837 {
namespace lna {
constexpr std::array<uint8_t, 8> lookup_8db_steps {
0b111, 0b011, 0b110, 0b010,
0b100, 0b000, 0b000, 0b000
};
static uint_fast8_t gain_ordinal(const int8_t db) {
const auto db_sat = gain_db_range.clip(db);
return lna::lookup_8db_steps[(db_sat >> 3) & 7];
}
} /* namespace lna */
namespace vga {
static uint_fast8_t gain_ordinal(const int8_t db) {
const auto db_sat = gain_db_range.clip(db);
return ((db_sat >> 1) & 0b11111) ^ 0b11111;
}
} /* namespace vga */
namespace tx {
static uint_fast8_t gain_ordinal(const int8_t db) {
const auto db_sat = gain_db_range.clip(db);
uint8_t value = db_sat & 0x0f;
value = (db_sat >= 16) ? (value | 0x20) : value;
value = (db_sat >= 32) ? (value | 0x10) : value;
return (value & 0b111111) ^ 0b111111;
}
} /* namespace tx */
namespace filter {
static uint_fast8_t bandwidth_ordinal(const uint32_t bandwidth) {
/* Determine filter setting that will provide bandwidth greater than or
* equal to requested bandwidth.
*/
return std::lower_bound(bandwidths.cbegin(), bandwidths.cend(), bandwidth) - bandwidths.cbegin();
}
} /* namespace filter */
/* Empirical testing indicates about 25us is necessary to get a valid
* temperature sense conversion from the ADC.
*/
constexpr float seconds_for_temperature_sense_adc_conversion = 30.0e-6;
constexpr halrtcnt_t ticks_for_temperature_sense_adc_conversion = (base_m4_clk_f * seconds_for_temperature_sense_adc_conversion + 1);
constexpr uint32_t reference_frequency = max2837_reference_f;
constexpr uint32_t pll_factor = 1.0 / (4.0 / 3.0 / reference_frequency) + 0.5;
void MAX2837::init() {
set_mode(Mode::Shutdown);
gpio_max2837_enable.output();
gpio_max2837_rxenable.output();
gpio_max2837_txenable.output();
_map.r.tx_gain.TXVGA_GAIN_SPI_EN = 1;
_map.r.tx_gain.TXVGA_GAIN_MSB_SPI_EN = 1;
_map.r.tx_gain.TXVGA_GAIN_SPI = 0x00;
_map.r.lpf_3_vga_1.VGAMUX_enable = 1;
_map.r.lpf_3_vga_1.VGA_EN = 1;
_map.r.hpfsm_3.HPC_STOP = 1; /* 1kHz */
_map.r.rx_top_rx_bias.LNAgain_SPI_EN = 1; /* control LNA gain from SPI */
_map.r.rxrf_2.L = 0b000;
_map.r.rx_top_rx_bias.VGAgain_SPI_EN = 1; /* control VGA gain from SPI */
_map.r.vga_2.VGA = 0b01010;
_map.r.lpf_3_vga_1.BUFF_VCM = 0b00; /* TODO: Check values out of ADC */
_map.r.lpf_1.LPF_EN = 1; /* Enable low-pass filter */
_map.r.lpf_1.ModeCtrl = 0b01; /* Rx LPF */
_map.r.lpf_1.FT = 0b0000; /* 5MHz LPF */
_map.r.spi_en.EN_SPI = 1; /* enable chip functions when ENABLE pin set */
_map.r.lo_gen.LOGEN_2GM = 0;
#if 0
_map.r.rxrf_1.LNA_EN = 1;
_map.r.rxrf_1.Mixer_EN = 1;
_map.r.rxrf_1.RxLO_EN = 1;
_map.r.rx_top.DOUT_DRVH = 0; /* slow down DOUT edges */
_map.r.hpfsm_4.DOUT_CSB_SEL = 0; /* DOUT not tri-stated, is independent of CSB */
_map.r.xtal_cfg.XTAL_CLKOUT_EN = 0; /* CLKOUT pin disabled. (Seems to have no effect.) */
#endif
_map.r.vga_3_rx_top.RSSI_EN_SPIenables = 1;
_map.r.vga_3_rx_top.RSSI_MODE = 1; /* RSSI independent of RXHP */
_dirty.set();
flush();
set_mode(Mode::Standby);
}
void MAX2837::set_mode(const Mode mode) {
gpio_max2837_enable.write(toUType(mode) & toUType(Mode::Mask_Enable));
gpio_max2837_rxenable.write(toUType(mode) & toUType(Mode::Mask_RxEnable));
gpio_max2837_txenable.write(toUType(mode) & toUType(Mode::Mask_TxEnable));
}
void MAX2837::flush() {
if( _dirty ) {
for(size_t n=0; n<reg_count; n++) {
if( _dirty[n] ) {
write(n, _map.w[n]);
}
}
_dirty.clear();
}
}
void MAX2837::flush_one(const Register reg) {
const auto reg_num = toUType(reg);
write(reg_num, _map.w[reg_num]);
_dirty.clear(reg_num);
}
void MAX2837::write(const address_t reg_num, const reg_t value) {
uint16_t t = (0U << 15) | (reg_num << 10) | (value & 0x3ffU);
_target.transfer(&t, 1);
}
reg_t MAX2837::read(const address_t reg_num) {
uint16_t t = (1U << 15) | (reg_num << 10);
_target.transfer(&t, 1U);
return t & 0x3ffU;
}
void MAX2837::write(const Register reg, const reg_t value) {
write(toUType(reg), value);
}
reg_t MAX2837::read(const Register reg) {
return read(toUType(reg));
}
void MAX2837::set_tx_vga_gain(const int_fast8_t db) {
_map.r.tx_gain.TXVGA_GAIN_SPI = tx::gain_ordinal(db);
_dirty[Register::TX_GAIN] = 1;
flush();
}
void MAX2837::set_lna_gain(const int_fast8_t db) {
_map.r.rxrf_2.L = lna::gain_ordinal(db);
_dirty[Register::RXRF_2] = 1;
flush();
}
void MAX2837::set_vga_gain(const int_fast8_t db) {
_map.r.vga_2.VGA = vga::gain_ordinal(db);
_dirty[Register::VGA_2] = 1;
flush();
}
void MAX2837::set_lpf_rf_bandwidth(const uint32_t bandwidth_minimum) {
_map.r.lpf_1.FT = filter::bandwidth_ordinal(bandwidth_minimum);
_dirty[Register::LPF_1] = 1;
flush();
}
bool MAX2837::set_frequency(const rf::Frequency lo_frequency) {
/* TODO: This is a sad implementation. Refactor. */
if( lo::band[0].contains(lo_frequency) ) {
_map.r.syn_int_div.LOGEN_BSW = 0b00; /* 2300 - 2399.99MHz */
_map.r.rxrf_1.LNAband = 0; /* 2.3 - 2.5GHz */
} else if( lo::band[1].contains(lo_frequency) ) {
_map.r.syn_int_div.LOGEN_BSW = 0b01; /* 2400 - 2499.99MHz */
_map.r.rxrf_1.LNAband = 0; /* 2.3 - 2.5GHz */
} else if( lo::band[2].contains(lo_frequency) ) {
_map.r.syn_int_div.LOGEN_BSW = 0b10; /* 2500 - 2599.99MHz */
_map.r.rxrf_1.LNAband = 1; /* 2.5 - 2.7GHz */
} else if( lo::band[3].contains(lo_frequency) ) {
_map.r.syn_int_div.LOGEN_BSW = 0b11; /* 2600 - 2700Hz */
_map.r.rxrf_1.LNAband = 1; /* 2.5 - 2.7GHz */
} else {
return false;
}
_dirty[Register::SYN_INT_DIV] = 1;
_dirty[Register::RXRF_1] = 1;
const uint64_t div_q20 = (lo_frequency * (1 << 20)) / pll_factor;
_map.r.syn_int_div.SYN_INTDIV = div_q20 >> 20;
_dirty[Register::SYN_INT_DIV] = 1;
_map.r.syn_fr_div_2.SYN_FRDIV_19_10 = (div_q20 >> 10) & 0x3ff;
_dirty[Register::SYN_FR_DIV_2] = 1;
/* flush to commit high FRDIV first, as low FRDIV commits the change */
flush();
_map.r.syn_fr_div_1.SYN_FRDIV_9_0 = (div_q20 & 0x3ff);
_dirty[Register::SYN_FR_DIV_1] = 1;
flush();
return true;
}
void MAX2837::set_rx_lo_iq_calibration(const size_t v) {
_map.r.rx_top_rx_bias.RX_IQERR_SPI_EN = 1;
_dirty[Register::RX_TOP_RX_BIAS] = 1;
_map.r.rxrf_2.iqerr_trim = v;
_dirty[Register::RXRF_2] = 1;
flush();
}
void MAX2837::set_rx_bias_trim(const size_t v) {
_map.r.rx_top_rx_bias.EN_Bias_Trim = 1;
_map.r.rx_top_rx_bias.BIAS_TRIM_SPI = v;
_dirty[Register::RX_TOP_RX_BIAS] = 1;
flush();
}
void MAX2837::set_vco_bias(const size_t v) {
_map.r.vco_cfg.VCO_BIAS_SPI_EN = 1;
_map.r.vco_cfg.VCO_BIAS_SPI = v;
_dirty[Register::VCO_CFG] = 1;
flush();
}
void MAX2837::set_rx_buff_vcm(const size_t v) {
_map.r.lpf_3_vga_1.BUFF_VCM = v;
_dirty[Register::LPF_3_VGA_1] = 1;
flush();
}
reg_t MAX2837::temp_sense() {
if( !_map.r.rx_top.ts_en ) {
_map.r.rx_top.ts_en = 1;
flush_one(Register::RX_TOP);
chThdSleepMilliseconds(1);
}
_map.r.rx_top.ts_adc_trigger = 1;
flush_one(Register::RX_TOP);
halPolledDelay(ticks_for_temperature_sense_adc_conversion);
const auto value = read(Register::TEMP_SENSE);
_map.r.rx_top.ts_adc_trigger = 0;
flush_one(Register::RX_TOP);
return value;
}
}

View File

@ -0,0 +1,914 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __MAX2837_H__
#define __MAX2837_H__
#include "gpio.hpp"
#include "spi_arbiter.hpp"
#include <cstdint>
#include <array>
#include "dirty_registers.hpp"
#include "rf_path.hpp"
#include "utility.hpp"
namespace max2837 {
enum class Mode {
Mask_Enable = 0b001,
Mask_RxEnable = 0b010,
Mask_TxEnable = 0b100,
Shutdown = 0b000,
Standby = Mask_Enable,
Receive = Mask_Enable | Mask_RxEnable,
Transmit = Mask_Enable | Mask_TxEnable,
};
/*************************************************************************/
namespace lo {
constexpr std::array<rf::FrequencyRange, 4> band { {
{ 2300000000, 2400000000 },
{ 2400000000, 2500000000 },
{ 2500000000, 2600000000 },
{ 2600000000, 2700000000 },
} };
} /* namespace lo */
/*************************************************************************/
namespace lna {
constexpr range_t<int8_t> gain_db_range { 0, 40 };
constexpr int8_t gain_db_step = 8;
constexpr std::array<rf::FrequencyRange, 2> band { {
{ 2300000000, 2500000000 },
{ 2500000000, 2700000000 },
} };
} /* namespace lna */
/*************************************************************************/
namespace vga {
constexpr range_t<int8_t> gain_db_range { 0, 62 };
constexpr int8_t gain_db_step = 2;
} /* namespace vga */
/*************************************************************************/
namespace tx {
constexpr range_t<int8_t> gain_db_range { 0, 47 };
constexpr int8_t gain_db_step = 1;
}
/*************************************************************************/
namespace filter {
constexpr std::array<uint32_t, 16> bandwidths {
/* Assumption: these values are in ascending order */
1750000,
2500000, /* Some documentation says 2.25MHz */
3500000,
5000000,
5500000,
6000000,
7000000,
8000000,
9000000,
10000000,
12000000,
14000000,
15000000,
20000000,
24000000,
28000000,
};
constexpr auto bandwidth_minimum = bandwidths[0];
constexpr auto bandwidth_maximum = bandwidths[bandwidths.size() - 1];
} /* namespace filter */
/*************************************************************************/
using reg_t = uint16_t;
using address_t = uint8_t;
constexpr size_t reg_count = 32;
enum class Register : address_t {
RXRF_1 = 0,
RXRF_2 = 1,
LPF_1 = 2,
LPF_2 = 3,
LPF_3_VGA_1 = 4,
VGA_2 = 5,
VGA_3_RX_TOP = 6,
TEMP_SENSE = 7,
RX_TOP_RX_BIAS = 8,
RX_TOP = 9,
TX_TOP_1 = 10,
TX_TOP_2 = 11,
HPFSM_1 = 12,
HPFSM_2 = 13,
HPFSM_3 = 14,
HPFSM_4 = 15,
SPI_EN = 16,
SYN_FR_DIV_1 = 17,
SYN_FR_DIV_2 = 18,
SYN_INT_DIV = 19,
SYN_CFG_1 = 20,
SYN_CFG_2 = 21,
VAS_CFG = 22,
LO_MISC = 23,
XTAL_CFG = 24,
VCO_CFG = 25,
LO_GEN = 26,
PA_DRV_PA_DAC = 27,
PA_DAC = 28,
TX_GAIN = 29,
TX_LO_IQ = 30,
TX_DC_CORR = 31,
};
struct RXRF_1_Type {
reg_t LNA_EN : 1;
reg_t Mixer_EN : 1;
reg_t RxLO_EN : 1;
reg_t Lbias : 2;
reg_t Mbias : 2;
reg_t buf : 2;
reg_t LNAband : 1;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(RXRF_1_Type) == sizeof(reg_t), "RXRF_1_Type wrong size");
struct RXRF_2_Type {
reg_t LNAtune : 1;
reg_t LNAde_Q : 1;
reg_t L : 3;
reg_t iqerr_trim : 5;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(RXRF_2_Type) == sizeof(reg_t), "RXRF_2_Type wrong size");
struct LPF_1_Type {
reg_t LPF_EN : 1;
reg_t TxBB_EN : 1;
reg_t ModeCtrl : 2;
reg_t FT : 4;
reg_t dF : 2;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(LPF_1_Type) == sizeof(reg_t), "LPF_1_Type wrong size");
struct LPF_2_Type {
reg_t PT_SPI : 4;
reg_t Bqd : 3;
reg_t TxRPCM : 3;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(LPF_2_Type) == sizeof(reg_t), "LPF_2_Type wrong size");
struct LPF_3_VGA_1_Type {
reg_t RP : 2;
reg_t TxBuff : 2;
reg_t VGA_EN : 1;
reg_t VGAMUX_enable : 1;
reg_t BUFF_Curr : 2;
reg_t BUFF_VCM : 2;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(LPF_3_VGA_1_Type) == sizeof(reg_t), "LPF_3_VGA_1_Type wrong size");
struct VGA_2_Type {
reg_t VGA : 5;
reg_t sel_In1_In2 : 1;
reg_t turbo15n20 : 1;
reg_t VGA_Curr : 2;
reg_t fuse_arm : 1;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(VGA_2_Type) == sizeof(reg_t), "VGA_2_Type wrong size");
struct VGA_3_RX_TOP_Type {
reg_t RESERVED0 : 6;
reg_t RSSI_EN_SPIenables : 1;
reg_t RSSI_MUX : 1;
reg_t RSSI_MODE : 1;
reg_t LPF_MODE_SEL : 1;
reg_t RESERVED1 : 6;
};
static_assert(sizeof(VGA_3_RX_TOP_Type) == sizeof(reg_t), "VGA_3_RX_TOP_Type wrong size");
struct TEMP_SENSE_Type {
reg_t ts_adc : 5;
reg_t RESERVED0 : 1;
reg_t PLL_test_output : 1;
reg_t VAS_test_output : 1;
reg_t HPFSM_test_output : 1;
reg_t LOGEN_trim_divider_test_output : 1;
reg_t RESERVED1 : 6;
};
static_assert(sizeof(TEMP_SENSE_Type) == sizeof(reg_t), "TEMP_SENSE_Type wrong size");
struct RX_TOP_RX_BIAS_Type {
reg_t LNAgain_SPI_EN : 1;
reg_t VGAgain_SPI_EN : 1;
reg_t EN_Bias_Trim : 1;
reg_t BIAS_TRIM_SPI : 5;
reg_t BIAS_TRIM_CNTRL : 1;
reg_t RX_IQERR_SPI_EN : 1;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(RX_TOP_RX_BIAS_Type) == sizeof(reg_t), "RX_TOP_RX_BIAS_Type wrong size");
struct RX_TOP_Type {
reg_t ts_adc_trigger : 1;
reg_t ts_en : 1;
reg_t LPFtrim_SPI_EN : 1;
reg_t DOUT_DRVH : 1;
reg_t DOUT_PU : 1;
reg_t DOUT_SEL : 3;
reg_t fuse_th : 1;
reg_t fuse_burn_gkt : 1;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(RX_TOP_Type) == sizeof(reg_t), "RX_TOP_Type wrong size");
struct TX_TOP_1_Type {
reg_t RESERVED0 : 1;
reg_t TXCAL_GAIN : 2;
reg_t TXCAL_V2I_FILT : 3;
reg_t TX_BIAS_ADJ : 2;
reg_t RESERVED1 : 2;
reg_t RESERVED2 : 6;
};
static_assert(sizeof(TX_TOP_1_Type) == sizeof(reg_t), "TX_TOP_1_Type wrong size");
struct TX_TOP_2_Type {
reg_t AMD_SPI_EN : 1;
reg_t TXMXR_V2I_GAIN : 4;
reg_t RESERVED0 : 5;
reg_t RESERVED1 : 6;
};
static_assert(sizeof(TX_TOP_2_Type) == sizeof(reg_t), "TX_TOP_2_Type wrong size");
struct HPFSM_1_Type {
reg_t HPC_10M : 2;
reg_t HPC_10M_GAIN : 2;
reg_t HPC_600k : 3;
reg_t HPC_600k_GAIN : 3;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(HPFSM_1_Type) == sizeof(reg_t), "HPFSM_1_Type wrong size");
struct HPFSM_2_Type {
reg_t HPC_100k : 2;
reg_t HPC_100k_GAIN : 2;
reg_t HPC_30k : 2;
reg_t HPC_30k_GAIN : 2;
reg_t HPC_1k : 2;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(HPFSM_2_Type) == sizeof(reg_t), "HPFSM_2_Type wrong size");
struct HPFSM_3_Type {
reg_t HPC_1k_GAIN : 2;
reg_t HPC_DELAY : 2;
reg_t HPC_STOP : 2;
reg_t HPC_STOP_M2 : 2;
reg_t HPC_RXGAIN_EN : 1;
reg_t HPC_MODE : 1;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(HPFSM_3_Type) == sizeof(reg_t), "HPFSM_3_Type wrong size");
struct HPFSM_4_Type {
reg_t HPC_DIVH : 1;
reg_t HPC_TST : 5;
reg_t HPC_SEQ_BYP : 1;
reg_t DOUT_CSB_SEL : 1;
reg_t RESERVED0 : 2;
reg_t RESERVED1 : 6;
};
static_assert(sizeof(HPFSM_4_Type) == sizeof(reg_t), "HPFSM_4_Type wrong size");
struct SPI_EN_Type {
reg_t EN_SPI : 1;
reg_t CAL_SPI : 1;
reg_t LOGEN_SPI_EN : 1;
reg_t SYN_SPI_EN : 1;
reg_t VAS_SPI_EN : 1;
reg_t PADRV_SPI_EN : 1;
reg_t PADAC_SPI_EN : 1;
reg_t PADAC_TX_EN : 1;
reg_t TXMX_SPI_EN : 1;
reg_t TXLO_SPI_EN : 1;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(SPI_EN_Type) == sizeof(reg_t), "SPI_EN_Type wrong size");
struct SYN_FR_DIV_1_Type {
reg_t SYN_FRDIV_9_0 : 10;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(SYN_FR_DIV_1_Type) == sizeof(reg_t), "SYN_FR_DIV_1_Type wrong size");
struct SYN_FR_DIV_2_Type {
reg_t SYN_FRDIV_19_10 : 10;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(SYN_FR_DIV_2_Type) == sizeof(reg_t), "SYN_FR_DIV_2_Type wrong size");
struct SYN_INT_DIV_Type {
reg_t SYN_INTDIV : 8;
reg_t LOGEN_BSW : 2;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(SYN_INT_DIV_Type) == sizeof(reg_t), "SYN_INT_DIV_Type wrong size");
struct SYN_CFG_1_Type {
reg_t SYN_MODE_FR_EN : 1;
reg_t SYN_REF_DIV_RATIO : 2;
reg_t SYN_CP_CURRENT : 2;
reg_t SYN_CLOCKOUT_DRIVE : 1;
reg_t SYN_TURBO_EN : 1;
reg_t CP_TRM_SET : 1;
reg_t CP_TRM_CODE : 2;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(SYN_CFG_1_Type) == sizeof(reg_t), "SYN_CFG_1_Type wrong size");
struct SYN_CFG_2_Type {
reg_t SYN_CP_COMMON_MODE_EN : 1;
reg_t SYN_PRESCALER_BIAS_BOOST : 1;
reg_t SYN_CP_BETA_CURRENT_COMP_EN : 1;
reg_t SYN_SD_CLK_SEL : 1;
reg_t SYN_CP_PW_ADJ : 1;
reg_t SYN_CP_LIN_CURRENT_SEL : 2;
reg_t SYN_TEST_OUT_SEL : 3;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(SYN_CFG_2_Type) == sizeof(reg_t), "SYN_CFG_2_Type wrong size");
struct VAS_CFG_Type {
reg_t VAS_MODE : 1;
reg_t VAS_RELOCK_SEL : 1;
reg_t VAS_DIV : 3;
reg_t VAS_DLY : 2;
reg_t VAS_TRIG_EN : 1;
reg_t VAS_ADE : 1;
reg_t VAS_ADL_SPI : 1;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(VAS_CFG_Type) == sizeof(reg_t), "VAS_CFG_Type wrong size");
struct LO_MISC_Type {
reg_t VAS_SPI : 5;
reg_t XTAL_BIAS_SEL : 2;
reg_t XTAL_E2C_BIAS_SEL : 1;
reg_t VAS_SE : 1;
reg_t VCO_SPI_EN : 1;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(LO_MISC_Type) == sizeof(reg_t), "LO_MISC_Type wrong size");
struct XTAL_CFG_Type {
reg_t XTAL_FTUNE : 7;
reg_t XTAL_CLKOUT_EN : 1;
reg_t XTAL_CLKOUT_DIV : 1;
reg_t XTAL_CORE_EN : 1;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(XTAL_CFG_Type) == sizeof(reg_t), "XTAL_CFG_Type wrong size");
struct VCO_CFG_Type {
reg_t VCO_BIAS_SPI_EN : 1;
reg_t VCO_BIAS_SPI : 4;
reg_t VCO_CMEN : 1;
reg_t VCO_PDET_TST : 2;
reg_t VCO_BUF_BIASH : 2;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(VCO_CFG_Type) == sizeof(reg_t), "VCO_CFG_Type wrong size");
struct LO_GEN_Type {
reg_t LOGEN_BIASH1 : 2;
reg_t LOGEN_BIASH2 : 1;
reg_t LOGEN_2GM : 1;
reg_t LOGEN_TRIM1 : 1;
reg_t LOGEN_TRIM2 : 1;
reg_t VAS_TST : 4;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(LO_GEN_Type) == sizeof(reg_t), "LO_GEN_Type wrong size");
struct PA_DRV_PA_DAC_Type {
reg_t PADRV_BIAS : 3;
reg_t PADRV_DOWN_SPI_EN : 1;
reg_t PADRV_DOWN_SPI_SEL : 1;
reg_t PADAC_IV : 1;
reg_t PADAC_VMODE : 1;
reg_t PADAC_DIVH : 1;
reg_t TXGATE_EN : 1;
reg_t TX_DCCORR_EN : 1;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(PA_DRV_PA_DAC_Type) == sizeof(reg_t), "PA_DRV_PA_DAC_Type wrong size");
struct PA_DAC_Type {
reg_t PADAC_BIAS : 6;
reg_t PADAC_DLY : 4;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(PA_DAC_Type) == sizeof(reg_t), "PA_DAC_Type wrong size");
struct TX_GAIN_Type {
reg_t TXVGA_GAIN_SPI_EN : 1;
reg_t TXVGA_GAIN_MSB_SPI_EN : 1;
reg_t TX_DCCORR_SPI_EN : 1;
reg_t FUSE_ARM : 1;
reg_t TXVGA_GAIN_SPI : 6;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(TX_GAIN_Type) == sizeof(reg_t), "TX_GAIN_Type wrong size");
struct TX_LO_IQ_Type {
reg_t TXLO_IQ_SPI : 5;
reg_t TXLO_IQ_SPI_EN : 1;
reg_t TXLO_BUFF : 2;
reg_t FUSE_GKT : 1;
reg_t FUSE_RTH : 1;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(TX_LO_IQ_Type) == sizeof(reg_t), "TX_LO_IQ_Type wrong size");
struct TX_DC_CORR_Type {
reg_t TX_DCCORR_I : 5;
reg_t TX_DCCORR_Q : 5;
reg_t RESERVED0 : 6;
};
static_assert(sizeof(TX_DC_CORR_Type) == sizeof(reg_t), "TX_DC_CORR_Type wrong size");
struct Register_Type {
RXRF_1_Type rxrf_1; /* 0 */
RXRF_2_Type rxrf_2;
LPF_1_Type lpf_1;
LPF_2_Type lpf_2;
LPF_3_VGA_1_Type lpf_3_vga_1; /* 4 */
VGA_2_Type vga_2;
VGA_3_RX_TOP_Type vga_3_rx_top;
TEMP_SENSE_Type temp_sense;
RX_TOP_RX_BIAS_Type rx_top_rx_bias; /* 8 */
RX_TOP_Type rx_top;
TX_TOP_1_Type tx_top_1;
TX_TOP_2_Type tx_top_2;
HPFSM_1_Type hpfsm_1; /* 12 */
HPFSM_2_Type hpfsm_2;
HPFSM_3_Type hpfsm_3;
HPFSM_4_Type hpfsm_4;
SPI_EN_Type spi_en; /* 16 */
SYN_FR_DIV_1_Type syn_fr_div_1;
SYN_FR_DIV_2_Type syn_fr_div_2;
SYN_INT_DIV_Type syn_int_div;
SYN_CFG_1_Type syn_cfg_1; /* 20 */
SYN_CFG_2_Type syn_cfg_2;
VAS_CFG_Type vas_cfg;
LO_MISC_Type lo_misc;
XTAL_CFG_Type xtal_cfg; /* 24 */
VCO_CFG_Type vco_cfg;
LO_GEN_Type lo_gen;
PA_DRV_PA_DAC_Type pa_drv_pa_dac;
PA_DAC_Type pa_dac; /* 28 */
TX_GAIN_Type tx_gain;
TX_LO_IQ_Type tx_lo_iq;
TX_DC_CORR_Type tx_dc_corr;
};
static_assert(sizeof(Register_Type) == reg_count * sizeof(reg_t), "Register_Type wrong size");
struct RegisterMap {
constexpr RegisterMap(
Register_Type values
) : r(values)
{
}
union {
Register_Type r;
std::array<reg_t, reg_count> w;
};
};
static_assert(sizeof(RegisterMap) == reg_count * sizeof(reg_t), "RegisterMap type wrong size");
constexpr RegisterMap initial_register_values { Register_Type {
/* Best effort to reconcile default values specified in three
* different places in the MAX2837 documentation.
*/
.rxrf_1 = { /* 0 */
.LNA_EN = 0,
.Mixer_EN = 0,
.RxLO_EN = 0,
.Lbias = 0b10,
.Mbias = 0b10,
.buf = 0b10,
.LNAband = 0,
.RESERVED0 = 0,
},
.rxrf_2 = { /* 1 */
.LNAtune = 0,
.LNAde_Q = 1,
.L = 0b000,
.iqerr_trim = 0b00000,
.RESERVED0 = 0,
},
.lpf_1 = { /* 2 */
.LPF_EN = 0,
.TxBB_EN = 0,
.ModeCtrl = 0b01,
.FT = 0b1111,
.dF = 0b01,
.RESERVED0 = 0,
},
.lpf_2 = { /* 3 */
.PT_SPI = 0b1001,
.Bqd = 0b011,
.TxRPCM = 0b011,
.RESERVED0 = 0,
},
.lpf_3_vga_1 = { /* 4 */
.RP = 0b10,
.TxBuff = 0b10,
.VGA_EN = 0,
.VGAMUX_enable = 0,
.BUFF_Curr = 0b00,
.BUFF_VCM = 0b00,
.RESERVED0 = 0,
},
.vga_2 = { /* 5 */
.VGA = 0b00000,
.sel_In1_In2 = 0,
.turbo15n20 = 0,
.VGA_Curr = 0b01,
.fuse_arm = 0,
.RESERVED0 = 0,
},
.vga_3_rx_top = { /* 6 */
.RESERVED0 = 0b000110,
.RSSI_EN_SPIenables = 0,
.RSSI_MUX = 0,
.RSSI_MODE = 0,
.LPF_MODE_SEL = 0,
.RESERVED1 = 0,
},
.temp_sense = { /* 7 */
.ts_adc = 0b00000,
.RESERVED0 = 0,
.PLL_test_output = 0,
.VAS_test_output = 0,
.HPFSM_test_output = 0,
.LOGEN_trim_divider_test_output = 0,
.RESERVED1 = 0,
},
.rx_top_rx_bias = { /* 8 */
.LNAgain_SPI_EN = 0,
.VGAgain_SPI_EN = 0,
.EN_Bias_Trim = 0,
.BIAS_TRIM_SPI = 0b10000,
.BIAS_TRIM_CNTRL = 0,
.RX_IQERR_SPI_EN = 0,
.RESERVED0 = 0,
},
.rx_top = { /* 9 */
.ts_adc_trigger = 0,
.ts_en = 0,
.LPFtrim_SPI_EN = 0,
.DOUT_DRVH = 1, /* Documentation mismatch */
.DOUT_PU = 1,
.DOUT_SEL = 0b000,
.fuse_th = 0,
.fuse_burn_gkt = 0,
.RESERVED0 = 0,
},
.tx_top_1 = { /* 10 */
.RESERVED0 = 0,
.TXCAL_GAIN = 0b00,
.TXCAL_V2I_FILT = 0b011,
.TX_BIAS_ADJ = 0b01,
.RESERVED1 = 0b00,
.RESERVED2 = 0,
},
.tx_top_2 = { /* 11 */
.AMD_SPI_EN = 0,
.TXMXR_V2I_GAIN = 0b1011,
.RESERVED0 = 0b00000,
.RESERVED1 = 0,
},
.hpfsm_1 = { /* 12 */
.HPC_10M = 0b11,
.HPC_10M_GAIN = 0b11,
.HPC_600k = 0b100,
.HPC_600k_GAIN = 0b100,
.RESERVED0 = 0,
},
.hpfsm_2 = { /* 13 */
.HPC_100k = 0b00,
.HPC_100k_GAIN = 0b00,
.HPC_30k = 0b01,
.HPC_30k_GAIN = 0b01,
.HPC_1k = 0b01,
.RESERVED0 = 0,
},
.hpfsm_3 = { /* 14 */
.HPC_1k_GAIN = 0b01,
.HPC_DELAY = 0b01,
.HPC_STOP = 0b00,
.HPC_STOP_M2 = 0b11,
.HPC_RXGAIN_EN = 1,
.HPC_MODE = 0,
.RESERVED0 = 0,
},
.hpfsm_4 = { /* 15 */
.HPC_DIVH = 1,
.HPC_TST = 0b00000,
.HPC_SEQ_BYP = 0,
.DOUT_CSB_SEL = 1, /* Documentation mismatch */
.RESERVED0 = 0b00,
.RESERVED1 = 0,
},
.spi_en = { /* 16 */
.EN_SPI = 0,
.CAL_SPI = 0,
.LOGEN_SPI_EN = 1,
.SYN_SPI_EN = 1,
.VAS_SPI_EN = 1,
.PADRV_SPI_EN = 0,
.PADAC_SPI_EN = 0,
.PADAC_TX_EN = 0,
.TXMX_SPI_EN = 0,
.TXLO_SPI_EN = 0,
.RESERVED0 = 0,
},
.syn_fr_div_1 = { /* 17 */
.SYN_FRDIV_9_0 = 0b0101010101,
.RESERVED0 = 0,
},
.syn_fr_div_2 = { /* 18 */
.SYN_FRDIV_19_10 = 0b0101010101,
.RESERVED0 = 0,
},
.syn_int_div = { /* 19 */
.SYN_INTDIV = 0b01010011,
.LOGEN_BSW = 0b01,
.RESERVED0 = 0,
},
.syn_cfg_1 = { /* 20 */
.SYN_MODE_FR_EN = 1,
.SYN_REF_DIV_RATIO = 0b00,
.SYN_CP_CURRENT = 0b00,
.SYN_CLOCKOUT_DRIVE = 0,
.SYN_TURBO_EN = 1,
.CP_TRM_SET = 0,
.CP_TRM_CODE = 0b10,
.RESERVED0 = 0,
},
.syn_cfg_2 = { /* 21 */
.SYN_CP_COMMON_MODE_EN = 1,
.SYN_PRESCALER_BIAS_BOOST = 0,
.SYN_CP_BETA_CURRENT_COMP_EN = 1,
.SYN_SD_CLK_SEL = 1,
.SYN_CP_PW_ADJ = 0,
.SYN_CP_LIN_CURRENT_SEL = 0b01,
.SYN_TEST_OUT_SEL = 0b000,
.RESERVED0 = 0,
},
.vas_cfg = { /* 22 */
.VAS_MODE = 1,
.VAS_RELOCK_SEL = 0,
.VAS_DIV = 0b010,
.VAS_DLY = 0b01,
.VAS_TRIG_EN = 1,
.VAS_ADE = 1,
.VAS_ADL_SPI = 0,
.RESERVED0 = 0,
},
.lo_misc = { /* 23 */
.VAS_SPI = 0b01111,
.XTAL_BIAS_SEL = 0b10,
.XTAL_E2C_BIAS_SEL = 0,
.VAS_SE = 0,
.VCO_SPI_EN = 1,
.RESERVED0 = 0,
},
.xtal_cfg = { /* 24 */
.XTAL_FTUNE = 0b0000000,
.XTAL_CLKOUT_EN = 0, /* 1->0 to "turn off" CLKOUT pin. Doesn't seem to work though... */
.XTAL_CLKOUT_DIV = 1,
.XTAL_CORE_EN = 0,
.RESERVED0 = 0,
},
.vco_cfg = { /* 25 */
.VCO_BIAS_SPI_EN = 0,
.VCO_BIAS_SPI = 0b0000,
.VCO_CMEN = 0,
.VCO_PDET_TST = 0b00,
.VCO_BUF_BIASH = 0b01,
.RESERVED0 = 0,
},
.lo_gen = { /* 26 */
.LOGEN_BIASH1 = 0b10,
.LOGEN_BIASH2 = 0,
.LOGEN_2GM = 1,
.LOGEN_TRIM1 = 0,
.LOGEN_TRIM2 = 0,
.VAS_TST = 0b1111,
.RESERVED0 = 0,
},
.pa_drv_pa_dac = { /* 27 */
.PADRV_BIAS = 0b011,
.PADRV_DOWN_SPI_EN = 0,
.PADRV_DOWN_SPI_SEL = 0, /* Documentation mismatch */
.PADAC_IV = 1,
.PADAC_VMODE = 1,
.PADAC_DIVH = 1,
.TXGATE_EN = 1,
.TX_DCCORR_EN = 1,
.RESERVED0 = 0,
},
.pa_dac = { /* 28 */
.PADAC_BIAS = 0b000000,
.PADAC_DLY = 0b0011,
.RESERVED0 = 0,
},
.tx_gain = { /* 29 */
.TXVGA_GAIN_SPI_EN = 0,
.TXVGA_GAIN_MSB_SPI_EN = 0,
.TX_DCCORR_SPI_EN = 0,
.FUSE_ARM = 0,
.TXVGA_GAIN_SPI = 0b111111,
.RESERVED0 = 0,
},
.tx_lo_iq = { /* 30 */
.TXLO_IQ_SPI = 0b00000,
.TXLO_IQ_SPI_EN = 0,
.TXLO_BUFF = 0b10,
.FUSE_GKT = 0,
.FUSE_RTH = 0,
.RESERVED0 = 0,
},
.tx_dc_corr = { /* 31 */
.TX_DCCORR_I = 0b00000,
.TX_DCCORR_Q = 0b00000,
.RESERVED0 = 0,
},
} };
class MAX2837 {
public:
constexpr MAX2837(
spi::arbiter::Target& target
) : _target(target)
{
}
void init();
void set_mode(const Mode mode);
void set_tx_vga_gain(const int_fast8_t db);
void set_lna_gain(const int_fast8_t db);
void set_vga_gain(const int_fast8_t db);
void set_lpf_rf_bandwidth(const uint32_t bandwidth_minimum);
#if 0
void rx_cal() {
_map.r.spi_en.EN_SPI = 1;
_map.r.spi_en.CAL_SPI = 1;
flush_one(Register::SPI_EN);
_map.r.vga_3_rx_top.LPF_MODE_SEL = 1;
flush_one(Register::VGA_3_RX_TOP);
_map.r.lpf_1.ModeCtrl = 0b00;
flush_one(Register::LPF_1);
_map.r.lo_gen.LOGEN_2GM = 1;
flush_one(Register::LO_GEN);
chThdSleepMilliseconds(100);
_map.r.spi_en.CAL_SPI = 0;
flush_one(Register::SPI_EN);
_map.r.vga_3_rx_top.LPF_MODE_SEL = 0;
flush_one(Register::VGA_3_RX_TOP);
_map.r.lpf_1.ModeCtrl = 0b01;
flush_one(Register::LPF_1);
_map.r.lo_gen.LOGEN_2GM = 0;
flush_one(Register::LO_GEN);
}
void test_rx_offset(const size_t n) {
_map.r.hpfsm_4.HPC_TST = n;
_dirty[Register::HPFSM_4] = 1;
/*
_map.r.hpfsm_3.HPC_STOP = n;
_dirty[Register::HPFSM_3] = 1;
*/
flush();
}
#endif
bool set_frequency(const rf::Frequency lo_frequency);
void set_rx_lo_iq_calibration(const size_t v);
void set_rx_bias_trim(const size_t v);
void set_vco_bias(const size_t v);
void set_rx_buff_vcm(const size_t v);
reg_t temp_sense();
reg_t read(const address_t reg_num);
private:
spi::arbiter::Target& _target;
RegisterMap _map { initial_register_values };
DirtyRegisters<Register, reg_count> _dirty { };
void flush_one(const Register reg);
void write(const address_t reg_num, const reg_t value);
void write(const Register reg, const reg_t value);
reg_t read(const Register reg);
void flush();
};
}
#endif/*__MAX2837_H__*/

View File

@ -0,0 +1,36 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "max5864.hpp"
#include <cstdint>
#include <array>
#include "utility.hpp"
namespace max5864 {
void MAX5864::set_mode(const Mode mode) {
std::array<uint8_t, 1> command { toUType(mode) };
_target.transfer(command.data(), command.size());
}
}

View File

@ -0,0 +1,59 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __MAX5864_H__
#define __MAX5864_H__
#include "spi_arbiter.hpp"
namespace max5864 {
enum class Mode : uint8_t {
Shutdown = 0x00,
Idle = 0x01,
Receive = 0x02,
Transmit = 0x03,
Transceiver = 0x04,
Standby = 0x05,
};
class MAX5864 {
public:
constexpr MAX5864(
spi::arbiter::Target& target
) : _target(target)
{
}
void init() {
/* Shut down explicitly, as there is no other reset mechanism. */
set_mode(Mode::Shutdown);
}
void set_mode(const Mode mode);
private:
spi::arbiter::Target& _target;
};
}
#endif/*__MAX5864_H__*/

View File

@ -0,0 +1,281 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "rffc507x.hpp"
#include <array>
#include "utility.hpp"
#include "hackrf_hal.hpp"
#include "hackrf_gpio.hpp"
using namespace hackrf::one;
#include "hal.h"
namespace rffc507x {
/* Empirical tests indicate no minimum reset pulse width, but the speed
* of the processor and GPIO probably produce at least 20ns pulse width.
*/
constexpr float seconds_during_reset = 1.0e-6;
constexpr halrtcnt_t ticks_during_reset = (base_m4_clk_f * seconds_during_reset + 1);
/* Empirical testing indicates >3.5us delay required after reset, before
* registers can be reliably written. Make it 5us, just for fun. Tests were
* conducted at high temperatures (with a hair dryer) increased room
* temperature minimum delay of 2.9us to the requirement above.
*/
constexpr float seconds_after_reset = 5.0e-6;
constexpr halrtcnt_t ticks_after_reset = (base_m4_clk_f * seconds_after_reset + 1);
constexpr auto reference_frequency = rffc5072_reference_f;
namespace vco {
constexpr rf::FrequencyRange range { 2700000000, 5400000000 };
} /* namespace vco */
namespace lo {
constexpr size_t divider_log2_min = 0;
constexpr size_t divider_log2_max = 5;
constexpr size_t divider_min = 1U << divider_log2_min;
constexpr size_t divider_max = 1U << divider_log2_max;
constexpr rf::FrequencyRange range { vco::range.minimum / divider_max, vco::range.maximum / divider_min };
size_t divider_log2(const rf::Frequency lo_frequency) {
/* TODO: Error */
/*
if( lo::range.out_of_range(lo_frequency) ) {
return;
}
*/
/* Compute LO divider. */
auto lo_divider_log2 = lo::divider_log2_min;
auto vco_frequency = lo_frequency;
while( vco::range.below_range(vco_frequency) ) {
vco_frequency <<= 1;
lo_divider_log2 += 1;
}
return lo_divider_log2;
}
} /* namespace lo */
namespace prescaler {
constexpr rf::Frequency max_frequency = 1600000000U;
constexpr size_t divider_log2_min = 1;
constexpr size_t divider_log2_max = 2;
constexpr size_t divider_min = 1U << divider_log2_min;
constexpr size_t divider_max = 1U << divider_log2_max;
constexpr size_t divider_log2(const rf::Frequency vco_frequency) {
return (vco_frequency > (prescaler::divider_min * prescaler::max_frequency))
? prescaler::divider_log2_max
: prescaler::divider_log2_min
;
}
} /* namespace prescaler */
struct SynthConfig {
const size_t lo_divider_log2;
const size_t prescaler_divider_log2;
const uint64_t n_divider_q24;
static SynthConfig calculate(
const rf::Frequency lo_frequency
) {
/* RFFC507x frequency synthesizer is is accurate to about 2ppb (two parts
* per BILLION). There's not much point to worrying about rounding and
* tuning error, when it amounts to 8Hz at 5GHz!
*/
const size_t lo_divider_log2 = lo::divider_log2(lo_frequency);
const size_t lo_divider = 1U << lo_divider_log2;
const rf::Frequency vco_frequency = lo_frequency * lo_divider;
const size_t prescaler_divider_log2 = prescaler::divider_log2(vco_frequency);
const uint64_t prescaled_lo_q24 = vco_frequency << (24 - prescaler_divider_log2);
const uint64_t n_divider_q24 = prescaled_lo_q24 / reference_frequency;
return {
lo_divider_log2,
prescaler_divider_log2,
n_divider_q24,
};
}
};
/* Readback values, RFFC5072 rev A:
* 0000: 0x8a01 => dev_id=1000101000000 mrev_id=001
* 0001: 0x3f7c => lock=0 ct_cal=0111111 cp_cal=011111 ctfail=0 0
* 0010: 0x806f => v0_cal=10000000 v1_cal=01101111
* 0011: 0x0000 => rsm_state=00000 f_errflag=00
* 0100: 0x0000 => vco_count_l=0
* 0101: 0x0000 => vco_count_h=0
* 0110: 0xc000 => cal_fbi=1 cal_fbq=1
* 0111: 0x0000 => vco_sel=0 vco_tc_curve=0
*/
void RFFC507x::init() {
gpio_rffc5072_resetx.set();
gpio_rffc5072_resetx.output();
reset();
_bus.init();
_dirty.set();
flush();
}
void RFFC507x::reset() {
/* TODO: Is RESETB pin ignored if sdi_ctrl.sipin=1? Programming guide
* description of sdi_ctrl.sipin suggests the pin is not ignored.
*/
gpio_rffc5072_resetx.clear();
halPolledDelay(ticks_during_reset);
gpio_rffc5072_resetx.set();
halPolledDelay(ticks_after_reset);
}
void RFFC507x::flush() {
if( _dirty ) {
for(size_t i=0; i<_map.w.size(); i++) {
if( _dirty[i] ) {
write(i, _map.w[i]);
}
}
_dirty.clear();
}
}
void RFFC507x::write(const address_t reg_num, const spi::reg_t value) {
_bus.write(reg_num, value);
}
spi::reg_t RFFC507x::read(const address_t reg_num) {
return _bus.read(reg_num);
}
void RFFC507x::write(const Register reg, const spi::reg_t value) {
write(toUType(reg), value);
}
spi::reg_t RFFC507x::read(const Register reg) {
return read(toUType(reg));
}
void RFFC507x::flush_one(const Register reg) {
const auto reg_num = toUType(reg);
write(reg_num, _map.w[reg_num]);
_dirty.clear(reg_num);
}
void RFFC507x::enable() {
_map.r.sdi_ctrl.enbl = 1;
flush_one(Register::SDI_CTRL);
/* TODO: Reset PLLCPL after CT_CAL? */
/* TODO: After device is enabled and CT_cal is complete and VCO > 3.2GHz,
* change prescaler divider to 2, update synthesizer ratio, change
* lf.pllcpl from 3 to 2.
*/
}
void RFFC507x::disable() {
_map.r.sdi_ctrl.enbl = 0;
flush_one(Register::SDI_CTRL);
}
void RFFC507x::set_mixer_current(const uint8_t value) {
/* MIX IDD = 0b000 appears to turn the mixer completely off */
/* TODO: Adjust mixer current. Graphs in datasheet suggest:
* MIX_IDD=1 has lowest noise figure (10.1dB vs 13dB @ MIX_IDD=7).
* MIX_IDD=5 has highest IP3 (24dBm vs 10.3dBm @ MIX_IDD=1).
* MIX_IDD=5 has highest P1dB (11.8dBm vs 1.5dBm @ MIX_IDD=1).
* Mixer input impedance ~85 Ohms at MIX_IDD=4.
* Mixer input impedance inversely proportional to MIX_IDD.
* Balun balanced (mixer) side is 100 Ohms. Perhaps reduce MIX_IDD
* a bit to get 100 Ohms from mixer.
*/
_map.r.mix_cont.p1mixidd = value;
_map.r.mix_cont.p2mixidd = value;
flush_one(Register::MIX_CONT);
}
void RFFC507x::set_frequency(const rf::Frequency lo_frequency) {
const SynthConfig synth_config = SynthConfig::calculate(lo_frequency);
/* Boost charge pump leakage if VCO frequency > 3.2GHz, indicated by
* prescaler divider set to 4 (log2=2) instead of 2 (log2=1).
*/
if( synth_config.prescaler_divider_log2 == 2 ) {
_map.r.lf.pllcpl = 3;
} else {
_map.r.lf.pllcpl = 2;
}
flush_one(Register::LF);
_map.r.p2_freq1.p2n = synth_config.n_divider_q24 >> 24;
_map.r.p2_freq1.p2lodiv = synth_config.lo_divider_log2;
_map.r.p2_freq1.p2presc = synth_config.prescaler_divider_log2;
_map.r.p2_freq2.p2nmsb = (synth_config.n_divider_q24 >> 8) & 0xffff;
_map.r.p2_freq3.p2nlsb = synth_config.n_divider_q24 & 0xff;
_dirty[Register::P2_FREQ1] = 1;
_dirty[Register::P2_FREQ2] = 1;
_dirty[Register::P2_FREQ3] = 1;
flush();
}
void RFFC507x::set_gpo1(const bool new_value) {
if( new_value ) {
_map.r.gpo.p2gpo |= 1;
_map.r.gpo.p1gpo |= 1;
} else {
_map.r.gpo.p2gpo &= ~1;
_map.r.gpo.p1gpo &= ~1;
}
flush_one(Register::GPO);
}
spi::reg_t RFFC507x::readback(const Readback readback) {
/* TODO: This clobbers the rest of the DEV_CTRL register
* Time to implement bitfields for registers.
*/
_map.r.dev_ctrl.readsel = toUType(readback);
flush_one(Register::DEV_CTRL);
return read(Register::READBACK);
}
} /* namespace rffc507x */

View File

@ -0,0 +1,835 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __RFFC507X_H__
#define __RFFC507X_H__
#include "rffc507x_spi.hpp"
#include <cstdint>
#include <array>
#include "dirty_registers.hpp"
#include "rf_path.hpp"
namespace rffc507x {
using reg_t = spi::reg_t;
using address_t = spi::address_t;
constexpr size_t reg_count = 31;
enum class Register : address_t {
LF = 0x00,
XO = 0x01,
CAL_TIME = 0x02,
VCO_CTRL = 0x03,
CT_CAL1 = 0x04,
CT_CAL2 = 0x05,
PLL_CAL1 = 0x06,
PLL_CAL2 = 0x07,
VCO_AUTO = 0x08,
PLL_CTRL = 0x09,
PLL_BIAS = 0x0a,
MIX_CONT = 0x0b,
P1_FREQ1 = 0x0c,
P1_FREQ2 = 0x0d,
P1_FREQ3 = 0x0e,
P2_FREQ1 = 0x0f,
P2_FREQ2 = 0x10,
P2_FREQ3 = 0x11,
FN_CTRL = 0x12,
EXT_MOD = 0x13,
FMOD = 0x14,
SDI_CTRL = 0x15,
GPO = 0x16,
T_VCO = 0x17,
IQMOD1 = 0x18,
IQMOD2 = 0x19,
IQMOD3 = 0x1a,
IQMOD4 = 0x1b,
T_CTRL = 0x1c,
DEV_CTRL = 0x1d,
TEST = 0x1e,
READBACK = 0x1f,
};
enum class Readback : uint8_t {
DeviceID = 0b0000,
TuningCalibration = 0b0001,
TuningVoltage = 0b0010,
StateMachine = 0b0011,
VCOCountL = 0b0100,
VCOCountH = 0b0101,
DCOffsetCal = 0b0110,
VCOMode = 0b0111,
};
struct LF_Type {
reg_t pllcpl : 3;
reg_t p1cpdef : 6;
reg_t p2cpdef : 6;
reg_t lfact : 1;
};
static_assert(sizeof(LF_Type) == sizeof(reg_t), "LF_Type type wrong size");
struct XO_Type {
reg_t suwait : 10;
reg_t xocf : 1;
reg_t xoc : 4;
reg_t xoch : 1;
};
static_assert(sizeof(XO_Type) == sizeof(reg_t), "XO_Type type wrong size");
struct CAL_TIME_Type {
reg_t tkv2 : 4;
reg_t tkv1 : 4;
reg_t reserved0 : 2;
reg_t tct : 5;
reg_t wait : 1;
};
static_assert(sizeof(CAL_TIME_Type) == sizeof(reg_t), "CAL_TIME_Type type wrong size");
struct VCO_CTRL_Type {
reg_t reserved0 : 1;
reg_t icpup : 2;
reg_t refst : 1;
reg_t xoi3 : 1;
reg_t xoi2 : 1;
reg_t xoi1 : 1;
reg_t kvpol : 1;
reg_t kvrng : 1;
reg_t kvavg : 2;
reg_t clkpl : 1;
reg_t ctpol : 1;
reg_t ctavg : 2;
reg_t xtvco : 1;
};
static_assert(sizeof(VCO_CTRL_Type) == sizeof(reg_t), "VCO_CTRL_Type type wrong size");
struct CT_CAL1_Type {
reg_t p1ctdef : 7;
reg_t p1ct : 1;
reg_t p1ctv : 5;
reg_t p1ctgain : 3;
};
static_assert(sizeof(CT_CAL1_Type) == sizeof(reg_t), "CT_CAL1_Type type wrong size");
struct CT_CAL2_Type {
reg_t p2ctdef : 7;
reg_t p2ct : 1;
reg_t p2ctv : 5;
reg_t p2ctgain : 3;
};
static_assert(sizeof(CT_CAL2_Type) == sizeof(reg_t), "CT_CAL2_Type type wrong size");
struct PLL_CAL1_Type {
reg_t reserved0 : 2;
reg_t p1sgn : 1;
reg_t p1kvgain : 3;
reg_t p1dn : 9;
reg_t p1kv : 1;
};
static_assert(sizeof(PLL_CAL1_Type) == sizeof(reg_t), "PLL_CAL1_Type type wrong size");
struct PLL_CAL2_Type {
reg_t reserved0 : 2;
reg_t p2sgn : 1;
reg_t p2kvgain : 3;
reg_t p2dn : 9;
reg_t p2kv : 1;
};
static_assert(sizeof(PLL_CAL2_Type) == sizeof(reg_t), "PLL_CAL2_Type type wrong size");
struct VCO_AUTO_Type {
reg_t reserved0 : 1;
reg_t ctmin : 7;
reg_t ctmax : 7;
reg_t auto_ : 1;
};
static_assert(sizeof(VCO_AUTO_Type) == sizeof(reg_t), "VCO_AUTO_Type type wrong size");
struct PLL_CTRL_Type {
reg_t plldy : 2;
reg_t aloi : 1;
reg_t relok : 1;
reg_t ldlev : 1;
reg_t lden : 1;
reg_t tvco : 5;
reg_t pllst : 1;
reg_t clkdiv : 3;
reg_t divby : 1;
};
static_assert(sizeof(PLL_CTRL_Type) == sizeof(reg_t), "PLL_CTRL_Type type wrong size");
struct PLL_BIAS_Type {
reg_t p2vcoi : 3;
reg_t p2loi : 4;
reg_t reserved0 : 1;
reg_t p1vcoi : 3;
reg_t p1loi : 4;
reg_t reserved1 : 1;
};
static_assert(sizeof(PLL_BIAS_Type) == sizeof(reg_t), "PLL_BIAS_Type type wrong size");
struct MIX_CONT_Type {
reg_t reserved0 : 9;
reg_t p2mixidd : 3;
reg_t p1mixidd : 3;
reg_t fulld : 1;
};
static_assert(sizeof(MIX_CONT_Type) == sizeof(reg_t), "MIX_CONT_Type type wrong size");
struct P1_FREQ1_Type {
reg_t p1vcosel : 2;
reg_t p1presc : 2;
reg_t p1lodiv : 3;
reg_t p1n : 9;
};
static_assert(sizeof(P1_FREQ1_Type) == sizeof(reg_t), "P1_FREQ1_Type type wrong size");
struct P1_FREQ2_Type {
reg_t p1nmsb : 16;
};
static_assert(sizeof(P1_FREQ2_Type) == sizeof(reg_t), "P1_FREQ2_Type type wrong size");
struct P1_FREQ3_Type {
reg_t reserved0 : 8;
reg_t p1nlsb : 8;
};
static_assert(sizeof(P1_FREQ3_Type) == sizeof(reg_t), "P1_FREQ3_Type type wrong size");
struct P2_FREQ1_Type {
reg_t p2vcosel : 2;
reg_t p2presc : 2;
reg_t p2lodiv : 3;
reg_t p2n : 9;
};
static_assert(sizeof(P2_FREQ1_Type) == sizeof(reg_t), "P2_FREQ1_Type type wrong size");
struct P2_FREQ2_Type {
reg_t p2nmsb : 16;
};
static_assert(sizeof(P2_FREQ2_Type) == sizeof(reg_t), "P2_FREQ2_Type type wrong size");
struct P2_FREQ3_Type {
reg_t reserved0 : 8;
reg_t p2nlsb : 8;
};
static_assert(sizeof(P2_FREQ3_Type) == sizeof(reg_t), "P2_FREQ3_Type type wrong size");
struct FN_CTRL_Type {
reg_t reserved0 : 1;
reg_t tzps : 1;
reg_t dmode : 1;
reg_t fm : 1;
reg_t dith : 1;
reg_t mode : 1;
reg_t phsalndly : 2;
reg_t phsalngain : 3;
reg_t phaln : 1;
reg_t sdm : 2;
reg_t dithr : 1;
reg_t fnz : 1;
};
static_assert(sizeof(FN_CTRL_Type) == sizeof(reg_t), "FN_CTRL_Type type wrong size");
struct EXT_MOD_Type {
reg_t reserved0 : 10;
reg_t modstep : 4;
reg_t modsetup : 2;
};
static_assert(sizeof(EXT_MOD_Type) == sizeof(reg_t), "EXT_MOD_Type type wrong size");
struct FMOD_Type {
reg_t modulation : 16;
};
static_assert(sizeof(FMOD_Type) == sizeof(reg_t), "FMOD_Type type wrong size");
struct SDI_CTRL_Type {
reg_t reserved0 : 1;
reg_t reset : 1;
reg_t reserved1 : 9;
reg_t addr : 1;
reg_t fourwire : 1;
reg_t mode : 1;
reg_t enbl : 1;
reg_t sipin : 1;
};
static_assert(sizeof(SDI_CTRL_Type) == sizeof(reg_t), "SDI_CTRL_Type type wrong size");
struct GPO_Type {
reg_t lock : 1;
reg_t gate : 1;
reg_t p1gpo : 7;
reg_t p2gpo : 7;
};
static_assert(sizeof(GPO_Type) == sizeof(reg_t), "GPO_Type type wrong size");
struct T_VCO_Type {
reg_t reserved0 : 7;
reg_t curve_vco3 : 3;
reg_t curve_vco2 : 3;
reg_t curve_vco1 : 3;
};
static_assert(sizeof(T_VCO_Type) == sizeof(reg_t), "T_VCO_Type type wrong size");
struct IQMOD1_Type {
reg_t bufdc : 2;
reg_t divbias : 1;
reg_t calblk : 1;
reg_t calnul : 1;
reg_t calon : 1;
reg_t lobias : 2;
reg_t modbias : 3;
/* Also defined as ctrl : 5 */
reg_t modiv : 1;
reg_t mod : 1;
reg_t txlo : 1;
reg_t bbgm : 1;
reg_t ctrl : 1;
};
static_assert(sizeof(IQMOD1_Type) == sizeof(reg_t), "IQMOD1_Type type wrong size");
struct IQMOD2_Type {
reg_t modbuf : 2;
reg_t mod : 2;
reg_t calatten : 2;
reg_t rctune : 6;
reg_t bbatten : 4;
};
static_assert(sizeof(IQMOD2_Type) == sizeof(reg_t), "IQMOD2_Type type wrong size");
struct IQMOD3_Type {
/* Documentation error */
reg_t reserved0 : 3;
reg_t dacen : 1;
reg_t bufdacq : 6;
reg_t bufdaci : 6;
};
static_assert(sizeof(IQMOD3_Type) == sizeof(reg_t), "IQMOD3_Type type wrong size");
struct IQMOD4_Type {
/* Documentation error */
reg_t bufbias2 : 2;
reg_t bufbias1 : 2;
reg_t moddacq : 6;
reg_t moddaci : 6;
};
static_assert(sizeof(IQMOD4_Type) == sizeof(reg_t), "IQMOD4_Type type wrong size");
struct T_CTRL_Type {
reg_t reserved0 : 5;
reg_t v_test : 1;
reg_t ldo_by : 1;
reg_t ext_filt : 1;
reg_t ref_sel : 1;
reg_t filt_ctrl : 2;
reg_t fc_en : 1;
reg_t tbl_sel : 2;
reg_t tc_en : 2;
};
static_assert(sizeof(T_CTRL_Type) == sizeof(reg_t), "T_CTRL_Type type wrong size");
struct DEV_CTRL_Type {
reg_t reserved0 : 1;
reg_t bypas : 1;
reg_t ctclk : 1;
reg_t dac : 1;
reg_t cpd : 1;
reg_t cpu : 1;
reg_t rsmstopst : 5;
reg_t rsmst : 1;
reg_t readsel : 4;
};
static_assert(sizeof(DEV_CTRL_Type) == sizeof(reg_t), "DEV_CTRL_Type type wrong size");
struct TEST_Type {
reg_t lfsrd : 1;
reg_t rcbyp : 1;
reg_t rgbyp : 1;
reg_t lfsrt : 1;
reg_t lfsrgatetime : 4;
reg_t lfsrp : 1;
reg_t lfsr : 1;
reg_t tsel : 2;
reg_t tmux : 3;
reg_t ten : 1;
};
static_assert(sizeof(TEST_Type) == sizeof(reg_t), "TEST_Type type wrong size");
struct READBACK_0000_Type {
reg_t mrev_id : 3;
reg_t dev_id : 13;
};
static_assert(sizeof(READBACK_0000_Type) == sizeof(reg_t), "READBACK_0000_Type type wrong size");
struct READBACK_0001_Type {
reg_t reserved0 : 1;
reg_t ctfail : 1;
reg_t cp_cal : 6;
reg_t ct_cal : 7;
reg_t lock : 1;
};
static_assert(sizeof(READBACK_0001_Type) == sizeof(reg_t), "READBACK_0001_Type type wrong size");
struct READBACK_0010_Type {
reg_t v1_cal : 8;
reg_t v0_cal : 8;
};
static_assert(sizeof(READBACK_0010_Type) == sizeof(reg_t), "READBACK_0010_Type type wrong size");
struct READBACK_0011_Type {
reg_t reserved0 : 9;
reg_t f_errflag : 2;
reg_t rsm_state : 5;
};
static_assert(sizeof(READBACK_0011_Type) == sizeof(reg_t), "READBACK_0011_Type type wrong size");
struct READBACK_0100_Type {
reg_t vco_count_l : 16;
};
static_assert(sizeof(READBACK_0100_Type) == sizeof(reg_t), "READBACK_0100_Type type wrong size");
struct READBACK_0101_Type {
reg_t vco_count_h : 16;
};
static_assert(sizeof(READBACK_0101_Type) == sizeof(reg_t), "READBACK_0101_Type type wrong size");
struct READBACK_0110_Type {
reg_t reserved0 : 14;
reg_t cal_fbq : 1;
reg_t cal_fbi : 1;
};
static_assert(sizeof(READBACK_0110_Type) == sizeof(reg_t), "READBACK_0110_Type type wrong size");
struct READBACK_0111_Type {
reg_t reserved0 : 11;
reg_t vco_tc_curve : 3;
reg_t vco_sel : 2;
};
static_assert(sizeof(READBACK_0111_Type) == sizeof(reg_t), "READBACK_0111_Type type wrong size");
struct Register_Type {
LF_Type lf;
XO_Type xo;
CAL_TIME_Type cal_time;
VCO_CTRL_Type vco_ctrl;
CT_CAL1_Type ct_cal1;
CT_CAL2_Type ct_cal2;
PLL_CAL1_Type pll_cal1;
PLL_CAL2_Type pll_cal2;
VCO_AUTO_Type vco_auto;
PLL_CTRL_Type pll_ctrl;
PLL_BIAS_Type pll_bias;
MIX_CONT_Type mix_cont;
P1_FREQ1_Type p1_freq1;
P1_FREQ2_Type p1_freq2;
P1_FREQ3_Type p1_freq3;
P2_FREQ1_Type p2_freq1;
P2_FREQ2_Type p2_freq2;
P2_FREQ3_Type p2_freq3;
FN_CTRL_Type fn_ctrl;
EXT_MOD_Type ext_mod;
FMOD_Type fmod;
SDI_CTRL_Type sdi_ctrl;
GPO_Type gpo;
T_VCO_Type t_vco;
IQMOD1_Type iqmod1;
IQMOD2_Type iqmod2;
IQMOD3_Type iqmod3;
IQMOD4_Type iqmod4;
T_CTRL_Type t_ctrl;
DEV_CTRL_Type dev_ctrl;
TEST_Type test;
};
static_assert(sizeof(Register_Type) == reg_count * sizeof(reg_t), "Register_Type wrong size");
struct RegisterMap {
constexpr RegisterMap(
Register_Type values
) : r(values)
{
}
union {
Register_Type r;
std::array<reg_t, reg_count> w;
};
};
static_assert(sizeof(RegisterMap) == reg_count * sizeof(reg_t), "RegisterMap type wrong size");
#if 0
struct ReadbackType {
union {
READBACK_0000_Type readback_0000;
READBACK_0001_Type readback_0001;
READBACK_0010_Type readback_0010;
READBACK_0011_Type readback_0011;
READBACK_0100_Type readback_0100;
READBACK_0101_Type readback_0101;
READBACK_0110_Type readback_0110;
READBACK_0111_Type readback_0111;
reg_t w;
};
};
#endif
#if 0
/* Revision 1 devices (mrev_id = 001):
* RFFC2071/2072/5071/5072, RFMD2080/2081
*/
constexpr RegisterMap default_revision_1 { std::array<reg_t, reg_count> {
0xbefa, 0x4064, 0x9055, 0x2d02,
0xb0bf, 0xb0bf, 0x0028, 0x0028,
0xfc06, 0x8220, 0x0202, 0x4800,
0x2324, 0x6276, 0x2700, 0x2f16,
0x3b13, 0xb100, 0x2a80, 0x0000,
0x0000, 0x0000, 0x0000, 0x0000,
0x0283, 0xf00f, 0x0000, 0x000f,
0x0000, 0x1000, 0x0001,
} };
/* Revision 2 devices (mrev_id = 010):
* RFFC2071A/2072A/5071A/5072A
*/
constexpr RegisterMap default_revision_2 { std::array<reg_t, reg_count> {
0xbefa, 0x4064, 0x9055, 0x2d02,
0xacbf, 0xacbf, 0x0028, 0x0028,
0xff00, 0x8220, 0x0202, 0x4800,
0x1a94, 0xd89d, 0x8900, 0x1e84,
0x89d8, 0x9d00, 0x2a80, 0x0000,
0x0000, 0x0000, 0x0000, 0x4900,
0x0281, 0xf00f, 0x0000, 0x0005,
0xc840, 0x1000, 0x0005,
} };
#endif
constexpr RegisterMap default_hackrf_one { Register_Type {
/* Started with recommended defaults for revision 1 devices
* (mrev_id = 001), RFFC2071/2072/5071/5072, RFMD2080/2081.
* Modified according to mixer programming guide.
*/
.lf = { /* 0 */
.pllcpl = 0b010,
.p1cpdef = 0b011111,
.p2cpdef = 0b011111,
.lfact = 1,
},
.xo = { /* 1 */
.suwait = 0b0001100100,
.xocf = 0b0,
.xoc = 0b1000,
.xoch = 0b0,
},
.cal_time = { /* 2 */
.tkv2 = 0b0101,
.tkv1 = 0b0101,
.reserved0 = 0b00,
.tct = 0b00100,
.wait = 0b1,
},
.vco_ctrl = { /* 3 */
.reserved0 = 0b0,
.icpup = 0b01,
.refst = 0b0,
.xoi3 = 0b0,
.xoi2 = 0b0,
.xoi1 = 0b0,
.kvpol = 0b0,
.kvrng = 0b1,
.kvavg = 0b10,
.clkpl = 0b1,
.ctpol = 0b0,
.ctavg = 0b01,
.xtvco = 0b0,
},
.ct_cal1 = { /* 4 */
.p1ctdef = 0b0111111,
.p1ct = 0b1,
.p1ctv = 12, /* RFMD recommneded change: 16 -> 12 */
.p1ctgain = 0b101,
},
.ct_cal2 = { /* 5 */
.p2ctdef = 0b0111111,
.p2ct = 0b1,
.p2ctv = 12, /* RFMD recommneded change: 16 -> 12 */
.p2ctgain = 0b101,
},
.pll_cal1 = { /* 6 */
.reserved0 = 0b00,
.p1sgn = 0b0,
.p1kvgain = 0b101,
.p1dn = 0b000000000,
.p1kv = 0b0,
},
.pll_cal2 = { /* 7 */
.reserved0 = 0b00,
.p2sgn = 0b0,
.p2kvgain = 0b101,
.p2dn = 0b000000000,
.p2kv = 0b0,
},
.vco_auto = { /* 8 */
.reserved0 = 0b0,
.ctmin = 0, /* RFMD recommended change: 3 -> 0 */
.ctmax = 127, /* RFMD recommended change: 124 -> 127 */
.auto_ = 0b1,
},
.pll_ctrl = { /* 9 */
.plldy = 0b00,
.aloi = 0b0,
.relok = 0b0,
.ldlev = 0b0,
.lden = 0b1,
.tvco = 0b01000,
.pllst = 0b0,
.clkdiv = 0b000,
.divby = 0b1,
},
.pll_bias = { /* 10 */
.p2vcoi = 0b010,
.p2loi = 0b0000,
.reserved0 = 0b0,
.p1vcoi = 0b010,
.p1loi = 0b0000,
.reserved1 = 0b0,
},
.mix_cont = { /* 11 */
.reserved0 = 0b000000000,
.p2mixidd = 4,
.p1mixidd = 4,
.fulld = 0b0, /* Part on HackRF is half-duplex (single mixer) */
},
.p1_freq1 = { /* 12 */
.p1vcosel = 0b00, /* RFMD VCO bank 1 configuration from A series part */
.p1presc = 0b01,
.p1lodiv = 0b001,
.p1n = 0b000110101,
},
.p1_freq2 = { /* 13 */
.p1nmsb = 0xd89d, /* RFMD VCO bank 1 configuration from A series part */
},
.p1_freq3 = { /* 14 */
.reserved0 = 0b00000000, /* RFMD VCO bank 1 configuration from A series part */
.p1nlsb = 0x89,
},
.p2_freq1 = { /* 15 */
.p2vcosel = 0b00, /* RFMD VCO bank 2 configuration from A series part */
.p2presc = 0b01,
.p2lodiv = 0b000,
.p2n = 0b000111101,
},
.p2_freq2 = { /* 16 */
.p2nmsb = 0x89d8, /* RFMD VCO bank 2 configuration from A series part */
},
.p2_freq3 = { /* 17 */
.reserved0 = 0b00000000, /* RFMD VCO bank 2 configuration from A series part */
.p2nlsb = 0x9d,
},
.fn_ctrl = { /* 18 */
.reserved0 = 0b0,
.tzps = 0b0,
.dmode = 0b0,
.fm = 0b0,
.dith = 0b0,
.mode = 0b0,
.phsalndly = 0b10,
.phsalngain = 0b010,
.phaln = 0b1,
.sdm = 0b10,
.dithr = 0b0,
.fnz = 0b0,
},
.ext_mod = { /* 19 */
.reserved0 = 0b0000000000,
.modstep = 0b0000,
.modsetup = 0b00,
},
.fmod = { /* 20 */
.modulation = 0x0000,
},
.sdi_ctrl = { /* 21 */
.reserved0 = 0b0,
.reset = 0b0,
.reserved1 = 0b000000000,
.addr = 0b0,
.fourwire = 0b0, /* Use three pin SPI mode */
.mode = 0b1, /* Active PLL register bank 2, active mixer 2 */
.enbl = 0b0, /* Part is initially disabled */
.sipin = 0b1, /* Control MODE, ENBL from SPI bus */
},
.gpo = { /* 22 */
.lock = 0b1, /* Present LOCK signal on GPIO4/LD/DO, HackRF One test point P6 */
.gate = 0b1, /* GPOs active even when part is disabled (ENBL=0) */
.p1gpo = 0b0000001, /* Turn on GPO1 to turn *off* !ANT_BIAS (GPO numbering is one-based) */
.p2gpo = 0b0000001, /* Turn on GPO1 to turn *off* !ANT_BIAS (GPO numbering is one-based) */
},
.t_vco = { /* 23 */
.reserved0 = 0b0000000,
.curve_vco3 = 0b000,
.curve_vco2 = 0b000,
.curve_vco1 = 0b000,
},
.iqmod1 = { /* 24 */
.bufdc = 0b11,
.divbias = 0b0,
.calblk = 0b0,
.calnul = 0b0,
.calon = 0b0,
.lobias = 0b10,
.modbias = 0b010,
.modiv = 0b0,
.mod = 0b0,
.txlo = 0b0,
.bbgm = 0b0,
.ctrl = 0b0,
},
.iqmod2 = { /* 25 */
.modbuf = 0b11,
.mod = 0b11,
.calatten = 0b00,
.rctune = 0b000000,
.bbatten = 0b1111,
},
.iqmod3 = { /* 26 */
.reserved0 = 0b000,
.dacen = 0b0,
.bufdacq = 0b000000,
.bufdaci = 0b000000,
},
.iqmod4 = { /* 27 */
.bufbias2 = 0b11,
.bufbias1 = 0b11,
.moddacq = 0b000000,
.moddaci = 0b000000,
},
.t_ctrl = { /* 28 */
.reserved0 = 0b00000,
.v_test = 0b0,
.ldo_by = 0b0,
.ext_filt = 0b0,
.ref_sel = 0b0,
.filt_ctrl = 0b00,
.fc_en = 0b0,
.tbl_sel = 0b00,
.tc_en = 0b00,
},
.dev_ctrl = { /* 29 */
.reserved0 = 0b0,
.bypas = 0b0,
.ctclk = 0b0,
.dac = 0b0,
.cpd = 0b0,
.cpu = 0b0,
.rsmstopst = 0b00000,
.rsmst = 0b0,
.readsel = 0b0001,
},
.test = { /* 30 */
.lfsrd = 0b1,
.rcbyp = 0b0,
.rgbyp = 0b1, /* RFMD recommended change: 0 -> 1 */
.lfsrt = 0b0,
.lfsrgatetime = 0b0000,
.lfsrp = 0b0,
.lfsr = 0b0,
.tsel = 0b00,
.tmux = 0b000,
.ten = 0b0,
},
} };
class RFFC507x {
public:
void init();
void reset();
void flush();
void enable();
void disable();
void set_mixer_current(const uint8_t value);
void set_frequency(const rf::Frequency lo_frequency);
void set_gpo1(const bool new_value);
reg_t read(const address_t reg_num);
private:
spi::SPI _bus { };
RegisterMap _map { default_hackrf_one };
DirtyRegisters<Register, reg_count> _dirty { };
void write(const address_t reg_num, const reg_t value);
void write(const Register reg, const reg_t value);
reg_t read(const Register reg);
void flush_one(const Register reg);
reg_t readback(const Readback readback);
void init_for_best_performance();
};
} /* rffc507x */
#endif/*__RFFC507X_H__*/

View File

@ -0,0 +1,109 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "rffc507x_spi.hpp"
#include "utility.hpp"
#include "hackrf_gpio.hpp"
using namespace hackrf::one;
namespace rffc507x {
namespace spi {
void SPI::init() {
gpio_rffc5072_select.set();
gpio_rffc5072_clock.clear();
gpio_rffc5072_select.output();
gpio_rffc5072_clock.output();
gpio_rffc5072_data.input();
gpio_rffc5072_data.clear();
}
inline void SPI::select(const bool active) {
gpio_rffc5072_select.write(!active);
}
inline void SPI::direction_out() {
gpio_rffc5072_data.output();
}
inline void SPI::direction_in() {
gpio_rffc5072_data.input();
}
inline void SPI::write_bit(const bit_t value) {
gpio_rffc5072_data.write(value);
}
inline bit_t SPI::read_bit() {
return gpio_rffc5072_data.read() & 1;
}
inline bit_t SPI::transfer_bit(const bit_t bit_out) {
gpio_rffc5072_clock.clear();
write_bit(bit_out);
const bit_t bit_in = read_bit();
gpio_rffc5072_clock.set();
return bit_in;
}
data_t SPI::transfer_bits(const data_t data_out, const size_t count) {
data_t data_in = 0;
for(size_t i=0; i<count; i++) {
data_in = (data_in << 1) | transfer_bit((data_out >> (count - i - 1)) & 1);
}
return data_in;
}
data_t SPI::transfer_word(const Direction direction, const address_t address, const data_t data_out) {
select(true);
const data_t address_word =
((direction == Direction::Read) ? (1 << 7) : 0)
| (address & 0x7f)
;
direction_out();
transfer_bits(address_word, 9);
if( direction == Direction::Read ) {
direction_in();
transfer_bits(0, 2);
}
const data_t data_in = transfer_bits(data_out, 16);
if( direction == Direction::Write ) {
direction_in();
}
select(false);
transfer_bits(0, 2);
return data_in;
}
}
}

View File

@ -0,0 +1,70 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __RFFC507X_SPI_H__
#define __RFFC507X_SPI_H__
#include <cstdint>
#include <cstddef>
namespace rffc507x {
namespace spi {
using reg_t = uint16_t;
using address_t = uint8_t;
using bit_t = uint_fast8_t;
using data_t = uint32_t;
class SPI {
public:
enum class Direction {
Write = 0,
Read = 1,
};
void init();
reg_t read(const address_t address) {
return transfer_word(Direction::Read, address, 0);
}
void write(const address_t address, const reg_t value) {
transfer_word(Direction::Write, address, value);
}
private:
void select(const bool active);
void direction_out();
void direction_in();
void write_bit(const bit_t value);
bit_t read_bit();
bit_t transfer_bit(const bit_t bit_out);
data_t transfer_bits(const data_t data_out, const size_t count);
data_t transfer_word(const Direction direction, const address_t address, const data_t data_out);
};
} /* spi */
} /* rffc507x */
#endif/*__RFFC507X_SPI_H__*/

View File

@ -0,0 +1,105 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "si5351.hpp"
#include "utility.hpp"
#include <cstdint>
#include <array>
namespace si5351 {
void Si5351::reset() {
wait_for_device_ready();
write_register(Register::InterruptStatusSticky, 0x00);
write_register(Register::InterruptStatusMask, 0xf0);
disable_output_mask(0xff);
write_register(Register::OEBPinEnableControlMask, 0xff);
write_register(Register::PLLInputSource, 0x00);
set_clock_control({
ClockControl::power_off(), ClockControl::power_off(),
ClockControl::power_off(), ClockControl::power_off(),
ClockControl::power_off(), ClockControl::power_off(),
ClockControl::power_off(), ClockControl::power_off()
});
write(std::array<uint8_t, 70> { Register::CLK3_0DisableState });
write(std::array<uint8_t, 14>{
Register::SpreadSpectrumParameters_Base
});
write(std::array<uint8_t, 4>{
Register::VCXOParameters_Base
});
write(std::array<uint8_t, 7>{
Register::CLKInitialPhaseOffset_Base
});
write_register(Register::CrystalInternalLoadCapacitance, 0b11010010);
write_register(Register::FanoutEnable, 0x00);
reset_plls();
}
Si5351::regvalue_t Si5351::read_register(const uint8_t reg) {
const std::array<uint8_t, 1> tx { reg };
std::array<uint8_t, 1> rx { 0x00 };
_bus.transmit(_address, tx.data(), tx.size());
_bus.receive(_address, rx.data(), rx.size());
return rx[0];
}
void Si5351::set_ms_frequency(
const size_t ms_number,
const uint32_t frequency,
const uint32_t vco_frequency,
const size_t r_div
) {
/* TODO: Factor out the VCO frequency, which should be an attribute held
* by the Si5351 object.
*/
const uint32_t a = vco_frequency / frequency;
const uint32_t remainder = vco_frequency - (frequency * a);
const uint32_t denom = gcd(remainder, frequency);
const uint32_t b = remainder / denom;
const uint32_t c = frequency / denom;
/* TODO: Switch between integer and fractional modes depending on the
* values of a and b.
*/
const MultisynthFractional ms {
.f_src = vco_frequency,
.a = a,
.b = b,
.c = c,
.r_div = r_div,
};
const auto regs = ms.reg(ms_number);
write(regs);
}
} /* namespace si5351 */

View File

@ -0,0 +1,492 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __SI5351_H__
#define __SI5351_H__
#include <cstdint>
#include <array>
#include <algorithm>
#include "ch.h"
#include "hal.h"
#include "i2c_pp.hpp"
namespace si5351 {
using reg_t = uint8_t;
namespace Register {
enum {
DeviceStatus = 0,
InterruptStatusSticky = 1,
InterruptStatusMask = 2,
OutputEnableControl = 3,
OEBPinEnableControlMask = 9,
PLLInputSource = 15,
CLKControl_Base = 16,
CLKControl0 = 16,
CLKControl1 = 17,
CLKControl2 = 18,
CLKControl3 = 19,
CLKControl4 = 20,
CLKControl5 = 21,
CLKControl6 = 22,
CLKControl7 = 23,
CLK3_0DisableState = 24,
CLK7_4DisableState = 25,
MultisynthNAParameters_Base = 26,
MultisynthNBParameters_Base = 34,
Multisynth0Parameters_Base = 42,
Multisynth1Parameters_Base = 50,
Multisynth2Parameters_Base = 58,
Multisynth3Parameters_Base = 66,
Multisynth4Parameters_Base = 74,
Multisynth5Parameters_Base = 82,
Multisynth6Parameters = 90,
Multisynth7Parameters = 91,
Clock6And7OutputDivider = 92,
SpreadSpectrumParameters_Base = 149,
VCXOParameters_Base = 162,
CLKInitialPhaseOffset_Base = 165,
PLLReset = 177,
CrystalInternalLoadCapacitance = 183,
FanoutEnable = 187,
};
}
namespace DeviceStatus {
using Type = uint8_t;
enum {
REVID_Mask = (0b11 << 0),
LOS_Mask = (1 << 4),
LOS_ValidClockAtCLKIN = (0 << 4),
LOS_LossOfSignalAtCLKIN = (1 << 4),
LOL_A_Mask = (1 << 5),
LOL_A_PLLALocked = (0 << 5),
LOL_A_PLLAUnlocked = (1 << 5),
LOL_B_Mask = (1 << 6),
LOL_B_PLLBLocked = (0 << 6),
LOL_B_PLLBUnlocked = (1 << 6),
SYS_INIT_Mask = (1 << 7),
SYS_INIT_Complete = (0 << 7),
SYS_INIT_Initializing = (1 << 7),
};
}
struct ClockControl {
enum ClockCurrentDrive {
_2mA = 0b00,
_4mA = 0b01,
_6mA = 0b10,
_8mA = 0b11,
};
enum ClockSource {
Xtal = 0b00,
CLKIN = 0b01,
MS_Group = 0b10,
MS_Self = 0b11,
};
enum ClockInvert {
Normal = 0,
Invert = 1,
};
enum MultiSynthSource {
PLLA = 0,
PLLB = 1,
};
enum MultiSynthMode {
Fractional = 0,
Integer = 1,
};
enum ClockPowerDown {
Power_On = 0,
Power_Off = 1,
};
reg_t CLK_IDRV : 2;
reg_t CLK_SRC : 2;
reg_t CLK_INV : 1;
reg_t MS_SRC : 1;
reg_t MS_INT : 1;
reg_t CLK_PDN : 1;
constexpr ClockControl(
ClockCurrentDrive clk_idrv,
ClockSource clk_src,
ClockInvert clk_inv,
MultiSynthSource ms_src,
MultiSynthMode ms_int,
ClockPowerDown clk_pdn
) : CLK_IDRV(clk_idrv),
CLK_SRC(clk_src),
CLK_INV(clk_inv),
MS_SRC(ms_src),
MS_INT(ms_int),
CLK_PDN(clk_pdn)
{
}
ClockControl clk_src(const ClockSource value) const {
auto result = *this;
result.CLK_SRC = value;
return result;
}
ClockControl ms_src(const MultiSynthSource value) const {
auto result = *this;
result.MS_SRC = value;
return result;
}
ClockControl clk_pdn(const ClockPowerDown value) const {
auto result = *this;
result.CLK_PDN = value;
return result;
}
constexpr operator reg_t() {
return *reinterpret_cast<reg_t*>(this);
}
static constexpr ClockControl power_off() {
return {
ClockCurrentDrive::_2mA,
ClockSource::Xtal,
ClockInvert::Normal,
MultiSynthSource::PLLA,
MultiSynthMode::Fractional,
ClockPowerDown::Power_Off,
};
}
};
static_assert(sizeof(ClockControl) == 1, "ClockControl size is not eight bits");
using ClockControls = std::array<ClockControl, 8>;
namespace CrystalInternalLoadCapacitance {
using Type = uint8_t;
enum {
XTAL_CL_Mask = (0b11 << 6),
XTAL_CL_6pF = (0b01 << 6),
XTAL_CL_8pF = (0b10 << 6),
XTAL_CL_10pF = (0b11 << 6),
};
}
namespace PLLInputSource {
using Type = uint8_t;
enum {
PLLA_Source_Mask = (1 << 2),
PLLA_Source_XTAL = (0 << 2),
PLLA_Source_CLKIN = (1 << 2),
PLLB_Source_Mask = (1 << 3),
PLLB_Source_XTAL = (0 << 3),
PLLB_Source_CLKIN = (1 << 3),
CLKIN_Div_Mask = (0b11 << 6),
CLKIN_Div1 = (0b00 << 6),
CLKIN_Div2 = (0b01 << 6),
CLKIN_Div4 = (0b10 << 6),
CLKIN_Div8 = (0b11 << 6),
};
}
struct Inputs {
const uint32_t f_xtal;
const uint32_t f_clkin;
const uint32_t clkin_div;
constexpr uint32_t f_clkin_out() const {
return f_clkin / clkin_div;
}
};
using PLLReg = std::array<uint8_t, 9>;
struct PLL {
const uint32_t f_in;
const uint32_t a;
const uint32_t b;
const uint32_t c;
constexpr uint32_t f_vco() const {
return f_in * (a + (float)b / (float)c);
}
constexpr uint32_t p1() const {
return 128 * a + (uint32_t)(128 * (float)b / (float)c) - 512;
}
constexpr uint32_t p2() const {
return 128 * b - c * (uint32_t)(128 * (float)b / (float)c);
}
constexpr uint32_t p3() const {
return c;
}
constexpr PLLReg reg(const uint8_t pll_n) const {
return {
uint8_t(26 + (pll_n * 8)),
uint8_t((p3() >> 8) & 0xff),
uint8_t((p3() >> 0) & 0xff),
uint8_t((p1() >> 16) & 0x03),
uint8_t((p1() >> 8) & 0xff),
uint8_t((p1() >> 0) & 0xff),
uint8_t(
(((p3() >> 16) & 0x0f) << 4)
| ((p2() >> 16) & 0x0f)
),
uint8_t((p2() >> 8) & 0xff),
uint8_t((p2() >> 0) & 0xff),
};
}
};
using MultisynthFractionalReg = std::array<uint8_t, 9>;
struct MultisynthFractional {
const uint32_t f_src;
const uint32_t a;
const uint32_t b;
const uint32_t c;
const uint32_t r_div;
constexpr uint32_t p1() const {
return 128 * a + (uint32_t)(128 * (float)b / (float)c) - 512;
}
constexpr uint32_t p2() const {
return 128 * b - c * (uint32_t)(128 * (float)b / (float)c);
}
constexpr uint32_t p3() const {
return c;
}
constexpr uint32_t f_out() const {
return f_src / (a + (float)b / (float)c) / (1 << r_div);
}
constexpr MultisynthFractionalReg reg(const uint8_t multisynth_n) const {
return {
uint8_t(42 + (multisynth_n * 8)),
uint8_t((p3() >> 8) & 0xFF),
uint8_t((p3() >> 0) & 0xFF),
uint8_t((r_div << 4) | (0 << 2) | ((p1() >> 16) & 0x3)),
uint8_t((p1() >> 8) & 0xFF),
uint8_t((p1() >> 0) & 0xFF),
uint8_t((((p3() >> 16) & 0xF) << 4) | (((p2() >> 16) & 0xF) << 0)),
uint8_t((p2() >> 8) & 0xFF),
uint8_t((p2() >> 0) & 0xFF)
};
}
};
struct MultisynthInteger {
const uint32_t f_src;
const uint32_t a;
const uint32_t r_div;
constexpr uint8_t p1() const {
return a;
}
constexpr uint32_t f_out() const {
return f_src / a / (1 << r_div);
}
};
using Multisynth6And7Reg = std::array<uint8_t, 4>;
constexpr Multisynth6And7Reg ms6_7_reg(
const MultisynthInteger& ms6,
const MultisynthInteger& ms7
) {
return {
Register::Multisynth6Parameters,
uint8_t(ms6.p1() & 0xff),
uint8_t(ms7.p1() & 0xff),
uint8_t(((ms7.r_div & 7) << 4) | ((ms6.r_div & 7) << 0)),
};
}
class Si5351 {
public:
using regvalue_t = uint8_t;
constexpr Si5351(I2C& bus, I2C::address_t address) :
_clock_control({
ClockControl::power_off(), ClockControl::power_off(),
ClockControl::power_off(), ClockControl::power_off(),
ClockControl::power_off(), ClockControl::power_off(),
ClockControl::power_off(), ClockControl::power_off()
}),
_bus(bus),
_address(address),
_output_enable(0x00)
{
}
void reset();
uint8_t device_status() {
return read_register(Register::DeviceStatus);
}
void wait_for_device_ready() {
while(device_status() & 0x80);
}
bool clkin_loss_of_signal() {
return (device_status() >> 4) & 1;
}
void enable_fanout() {
write_register(Register::FanoutEnable, 0b11010000);
}
void reset_plls() {
// Datasheet recommends value 0xac, though the low nibble bits are not defined in AN619.
write_register(Register::PLLReset, 0xac);
}
regvalue_t read_register(const uint8_t reg);
template<size_t N>
void write(const std::array<uint8_t, N>& values) {
_bus.transmit(_address, values.data(), values.size());
}
void write_register(const uint8_t reg, const regvalue_t value) {
write(std::array<uint8_t, 2>{
reg, value
});
}
void write(const size_t ms_number, const MultisynthFractional& config) {
write(config.reg(ms_number));
}
void set_ms_frequency(
const size_t ms_number,
const uint32_t frequency,
const uint32_t vco_frequency,
const size_t r_div
);
void set_crystal_internal_load_capacitance(const CrystalInternalLoadCapacitance::Type xtal_cl) {
write_register(Register::CrystalInternalLoadCapacitance, xtal_cl);
}
void set_pll_input_sources(const PLLInputSource::Type value) {
write_register(Register::PLLInputSource, value);
}
void enable_output_mask(const uint8_t mask) {
_output_enable |= mask;
update_output_enable_control();
}
void enable_output(const size_t n) {
enable_output_mask(1 << n);
}
void disable_output_mask(const uint8_t mask) {
_output_enable &= ~mask;
update_output_enable_control();
}
void disable_output(const size_t n) {
disable_output_mask(1 << n);
}
void set_clock_control(const ClockControls& clock_control) {
_clock_control = clock_control;
update_all_clock_control();
}
void set_clock_control(const size_t n, const ClockControl clock_control) {
_clock_control[n] = clock_control;
write_register(Register::CLKControl_Base + n, _clock_control[n]);
}
void enable_clock(const size_t n) {
_clock_control[n].CLK_PDN = ClockControl::ClockPowerDown::Power_On;
write_register(Register::CLKControl_Base + n, _clock_control[n]);
}
void disable_clock(const size_t n) {
_clock_control[n].CLK_PDN = ClockControl::ClockPowerDown::Power_Off;
write_register(Register::CLKControl_Base + n, _clock_control[n]);
}
template<size_t N>
void write_registers(const uint8_t reg, const std::array<uint8_t, N>& values) {
std::array<uint8_t, N + 1> data;
data[0] = reg;
std::copy(values.cbegin(), values.cend(), data.begin() + 1);
write(data);
}
private:
ClockControls _clock_control;
I2C& _bus;
const I2C::address_t _address;
uint8_t _output_enable;
void update_output_enable_control() {
write_register(Register::OutputEnableControl, ~_output_enable);
}
void update_all_clock_control() {
write_registers(Register::CLKControl_Base, std::array<reg_t, 8> { {
_clock_control[0],
_clock_control[1],
_clock_control[2],
_clock_control[3],
_clock_control[4],
_clock_control[5],
_clock_control[6],
_clock_control[7],
} });
}
};
}
#endif/*__SI5351_H__*/

View File

@ -0,0 +1,77 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __SPI_ARBITER_H__
#define __SPI_ARBITER_H__
#include <cstddef>
#include "spi_pp.hpp"
namespace spi {
namespace arbiter {
class Arbiter {
public:
constexpr Arbiter(
SPI& bus
) : _bus(bus),
_config(nullptr)
{
}
void transfer(const SPIConfig* const config, void* const data, const size_t count) {
if( config != _config ) {
_bus.stop();
_bus.start(*config);
_config = config;
}
_bus.transfer(data, count);
}
private:
SPI& _bus;
const SPIConfig* _config;
};
class Target {
public:
constexpr Target(
Arbiter& arbiter,
const SPIConfig& config
) : _arbiter(arbiter),
_config(config)
{
}
void transfer(void* const data, const size_t count) {
_arbiter.transfer(&_config, data, count);
}
private:
Arbiter& _arbiter;
const SPIConfig _config;
};
} /* arbiter */
} /* spi */
#endif/*__SPI_ARBITER_H__*/

View File

@ -0,0 +1,22 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "spi_pp.hpp"

View File

@ -0,0 +1,56 @@
/*
* Copyright (C) 2014 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __SPI_PP_H__
#define __SPI_PP_H__
#include <cstdint>
#include "ch.h"
#include "hal.h"
class SPI {
public:
constexpr SPI(SPIDriver* const driver) :
_driver(driver) {
}
void start(const SPIConfig& config) {
spiStart(_driver, &config);
}
void stop() {
spiStop(_driver);
}
void transfer(void* const data, const size_t count) {
spiAcquireBus(_driver);
spiSelect(_driver);
spiExchange(_driver, count, data, data);
spiUnselect(_driver);
spiReleaseBus(_driver);
}
private:
SPIDriver* const _driver;
};
#endif/*__SPI_PP_H__*/

View File

@ -0,0 +1,86 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#include "touch.hpp"
#include <cstdint>
#include "adc.hpp"
#include "utility.hpp"
#include "hal.h"
using namespace lpc43xx;
#include "hackrf_hal.hpp"
using namespace hackrf::one;
#include "portapack_adc.hpp"
#include "portapack_shared_memory.hpp"
namespace touch {
namespace adc {
constexpr uint8_t adc0_sel =
(1 << portapack::adc0_touch_xp_input)
| (1 << portapack::adc0_touch_xn_input)
| (1 << portapack::adc0_touch_yp_input)
| (1 << portapack::adc0_touch_yn_input)
;
const auto adc0_interrupt_mask = flp2(adc0_sel);
constexpr lpc43xx::adc::CR adc0_cr {
.sel = adc0_sel,
.clkdiv = 49, /* 400kHz sample rate, 2.5us/sample @ 200MHz PCLK */
.resolution = 9, /* Ten clocks */
.edge = 0,
};
constexpr lpc43xx::adc::Config adc0_config {
.cr = adc0_cr,
};
void init() {
adc0::clock_enable();
adc0::interrupts_disable();
adc0::power_up(adc0_config);
adc0::interrupts_enable(adc0_interrupt_mask);
}
void start() {
adc0::start_burst();
}
// static constexpr bool monitor_overruns_and_not_dones = false;
Samples get() {
const auto xp_reg = LPC_ADC0->DR[portapack::adc0_touch_xp_input];
const auto xn_reg = LPC_ADC0->DR[portapack::adc0_touch_xn_input];
const auto yp_reg = LPC_ADC0->DR[portapack::adc0_touch_yp_input];
const auto yn_reg = LPC_ADC0->DR[portapack::adc0_touch_yn_input];
return {
(xp_reg >> 6) & 0x3ff,
(xn_reg >> 6) & 0x3ff,
(yp_reg >> 6) & 0x3ff,
(yn_reg >> 6) & 0x3ff,
};
}
} /* namespace adc */
} /* namespace touch */

View File

@ -0,0 +1,38 @@
/*
* Copyright (C) 2015 Jared Boone, ShareBrained Technology, Inc.
*
* This file is part of PortaPack.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; see the file COPYING. If not, write to
* the Free Software Foundation, Inc., 51 Franklin Street,
* Boston, MA 02110-1301, USA.
*/
#ifndef __TOUCH_ADC_H__
#define __TOUCH_ADC_H__
#include "touch.hpp"
namespace touch {
namespace adc {
void init();
void start();
Samples get();
} /* namespace adc */
} /* namespace touch */
#endif/*__TOUCH_ADC_H__*/