pull/53/head
Dave Crump 2016-11-18 17:36:57 +00:00
rodzic 34c01e41f1
commit b9044963b0
8 zmienionych plików z 935 dodań i 0 usunięć

BIN
bin/adf4351 100755

Plik binarny nie jest wyświetlany.

Wyświetl plik

@ -97,6 +97,7 @@ case "$MODE_OUTPUT" in
OUTPUT=videots
MODE=IQ
$PATHSCRIPT"/ctlfilter.sh"
$PATHSCRIPT"/ctlvco.sh"
#GAIN=0
;;
QPSKRF)

40
scripts/ctlvco.sh 100755
Wyświetl plik

@ -0,0 +1,40 @@
########## ctlvco.sh ############
# Called by a.sh in IQ mode to set ADF4351
# vco to correct frequency
############ Set Environment Variables ###############
PATHSCRIPT=/home/pi/rpidatv/scripts
PATHRPI=/home/pi/rpidatv/bin
CONFIGFILE=$PATHSCRIPT"/rpidatvconfig.txt"
############### Function to read Config File ###############
get_config_var() {
lua - "$1" "$2" <<EOF
local key=assert(arg[1])
local fn=assert(arg[2])
local file=assert(io.open(fn))
for line in file:lines() do
local val = line:match("^#?%s*"..key.."=(.*)$")
if (val ~= nil) then
print(val)
break
end
end
EOF
}
############### Read Frequency #########################
FREQM=$(get_config_var freqoutput $CONFIGFILE)
############### Call binary to set frequency ########
sudo $PATHRPI"/adf4351" $FREQM
### End ###
# Revert to a.sh #

Wyświetl plik

@ -0,0 +1,13 @@
all: adf4351
CFLAGS = -Wall -g -O2 -Wno-unused-variable
LDFLAGS = -lm -lrt -lpthread -lwiringPi
adf4351 : adf4351.h adf4351.c ctladf4351.c
$(CC) $(CFLAGS) -o adf4351 adf4351.c ctladf4351.c $(LDFLAGS)
clean:
rm -f *.o

BIN
src/adf4351/adf4351 100755

Plik binarny nie jest wyświetlany.

Wyświetl plik

@ -0,0 +1,591 @@
/***************************************************************************//**
* @file adf4350.c
* @brief Implementation of ADF4350 Driver.
* @author DBogdan (dragos.bogdan@analog.com)
*
********************************************************************************
* Copyright 2012-2015(c) Analog Devices, Inc.
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* - Neither the name of Analog Devices, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
* - The use of this software may or may not infringe the patent rights
* of one or more patent holders. This license does not release you
* from the requirement that you obtain separate licenses from these
* patent holders to use this software.
* - Use of the software either in source or binary form, must be run
* on or directly connected to an Analog Devices Inc. component.
*
* THIS SOFTWARE IS PROVIDED BY ANALOG DEVICES "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, NON-INFRINGEMENT,
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
* IN NO EVENT SHALL ANALOG DEVICES BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, INTELLECTUAL PROPERTY RIGHTS, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*******************************************************************************/
/* wiringPiSPI.c:
* Simplified SPI access routines
* Copyright (c) 2012-2015 Gordon Henderson
***********************************************************************
* This file is part of wiringPi:
* https://projects.drogon.net/raspberry-pi/wiringpi/
*
* wiringPi is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as
* published by the Free Software Foundation, either version 3 of the
* License, or (at your option) any later version.
*
* wiringPi 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 Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with wiringPi.
* If not, see <http://www.gnu.org/licenses/>.
***********************************************************************
*/
#include <stdint.h>
#include <unistd.h>
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <getopt.h>
#include <fcntl.h>
#include <sys/ioctl.h>
#include <linux/types.h>
#include <linux/spi/spidev.h>
#include <wiringPi.h>
#include "adf4351.h"
// The SPI bus parameters
// Variables as they need to be passed as pointers later on
const static char *spiDev0 = "/dev/spidev0.0" ;
const static char *spiDev1 = "/dev/spidev0.1" ;
const static uint8_t spiBPW = 8 ;
const static uint16_t spiDelay = 0 ;
static uint32_t spiSpeeds [2] ;
static int spiFds [2] ;
int SPIDataRW (int channel, unsigned char *data, int len)
{
struct spi_ioc_transfer spi ;
channel &= 1 ;
// Mentioned in spidev.h but not used in the original kernel documentation
// test program )-:
memset (&spi, 0, sizeof (spi)) ;
spi.tx_buf = (unsigned long)data ;
spi.rx_buf = (unsigned long)data ;
spi.len = len ;
spi.delay_usecs = spiDelay ;
spi.speed_hz = spiSpeeds [channel] ;
spi.bits_per_word = spiBPW ;
//return ioctl (spiFds [channel], SPI_IOC_MESSAGE(1), &spi) ;
return 0;
}
/***************************************************************************//**
* @brief Was used to open the spi device set up the SPI mode. Now unused
*
* @param data - int channel, int speed, int mode
*
* @return Always Returns 0
*******************************************************************************/
int SPISetupMode (int channel, int speed, int mode)
{
int fd ;
mode &= 3 ; // Mode is 0, 1, 2 or 3
channel &= 1 ; // Channel is 0 or 1
return 0;
}
/******************************************************************************/
/************************ Local variables and types ***************************/
/******************************************************************************/
static struct adf4350_state
{
struct adf4350_platform_data *pdata;
uint32_t clkin;
uint32_t chspc; /* Channel Spacing */
uint32_t fpfd; /* Phase Frequency Detector */
uint32_t min_out_freq;
uint32_t r0_fract;
uint32_t r0_int;
uint32_t r1_mod;
uint32_t r4_rf_div_sel;
uint32_t regs[6];
uint32_t regs_hw[6];
uint32_t val;
}adf4350_st;
uint8_t adf4350_slave_select;
/***************************************************************************//**
* @brief Writes 4 bytes (32 bits) of data to ADF4350.
*
* @param data - Data value to write
*
* @return Always Returns 0
*******************************************************************************/
int32_t adf4350_write(uint32_t data)
{
// Nominate pins using WiringPi numbers
// LE pin 27 wPi 30
// CLK pin 29 wPi 21
// Data pin 31 wPi 22
uint8_t LE_4351_GPIO = 30;
uint8_t CLK_4351_GPIO = 21;
uint8_t DATA_4351_GPIO = 22;
// Kick wiringPi into action. Essential!
//if (wiringPiSetup () == -1)
//printf("Wiring Pi not set up ");
// Set all nominated pins to outputs
pinMode(LE_4351_GPIO, OUTPUT);
pinMode(CLK_4351_GPIO, OUTPUT);
pinMode(DATA_4351_GPIO, OUTPUT);
// Set idle conditions
digitalWrite(LE_4351_GPIO, HIGH);
digitalWrite(CLK_4351_GPIO, LOW);
digitalWrite(DATA_4351_GPIO, LOW);
//Select device LE low
digitalWrite(LE_4351_GPIO, LOW);
printf(" ADF4351 Register (one of the five) Updated\n");
// Initialise loop
uint16_t i;
// Send all 32 bits
for (i = 0; i <32; i++)
{
// Test left-most bit
if (data & 0x80000000)
digitalWrite(DATA_4351_GPIO, HIGH);
else
digitalWrite(DATA_4351_GPIO, LOW);
// Pulse clock
digitalWrite(CLK_4351_GPIO, HIGH);
delay(1);
digitalWrite(CLK_4351_GPIO, LOW);
delay(1);
// shift data left so next bit will be leftmost
data <<= 1;
}
//Set ADF4351 LE high
digitalWrite(LE_4351_GPIO, HIGH);
return 0;
}
/***************************************************************************//**
* @brief Updates the registers values.
*
* @param st - The selected structure.
*
* @return Returns 0 in case of success or negative error code.
*******************************************************************************/
int32_t adf4350_sync_config(struct adf4350_state *st)
{
int32_t ret, i, doublebuf = 0;
for (i = ADF4350_REG5; i >= ADF4350_REG0; i--)
{
if ((st->regs_hw[i] != st->regs[i]) ||
((i == ADF4350_REG0) && doublebuf))
{
switch (i)
{
case ADF4350_REG1:
case ADF4350_REG4:
doublebuf = 1;
break;
}
st->val = (st->regs[i] | i);
ret = adf4350_write(st->val);
if (ret < 0)
return ret;
st->regs_hw[i] = st->regs[i];
}
}
return 0;
}
/***************************************************************************//**
* @brief Increases the R counter value until the ADF4350_MAX_FREQ_PFD is
* greater than PFD frequency.
*
* @param st - The selected structure.
* @param r_cnt - Initial r_cnt value.
*
* @return Returns 0 in case of success or negative error code.
*******************************************************************************/
int32_t adf4350_tune_r_cnt(struct adf4350_state *st, uint16_t r_cnt)
{
struct adf4350_platform_data *pdata = st->pdata;
do
{
r_cnt++;
st->fpfd = (st->clkin * (pdata->ref_doubler_en ? 2 : 1)) /
(r_cnt * (pdata->ref_div2_en ? 2 : 1));
} while (st->fpfd > ADF4350_MAX_FREQ_PFD);
return r_cnt;
}
/***************************************************************************//**
* @brief Computes the greatest common divider of two numbers
*
* @return Returns the gcd.
*******************************************************************************/
uint32_t gcd(uint32_t x, uint32_t y)
{
int32_t tmp;
tmp = y > x ? x : y;
while((x % tmp) || (y % tmp))
{
tmp--;
}
return tmp;
}
/***************************************************************************//**
* @brief Sets the ADF4350 frequency.
*
* @param st - The selected structure.
* @param freq - The desired frequency value.
*
* @return calculatedFrequency - The actual frequency value that was set.
*******************************************************************************/
int64_t adf4350_set_freq(struct adf4350_state *st, uint64_t freq)
{
struct adf4350_platform_data *pdata = st->pdata;
uint64_t tmp;
uint32_t div_gcd, prescaler, chspc;
uint16_t mdiv, r_cnt = 0;
uint8_t band_sel_div;
int32_t ret;
if ((freq > ADF4350_MAX_OUT_FREQ) || (freq < ADF4350_MIN_OUT_FREQ))
return -1;
if (freq > ADF4350_MAX_FREQ_45_PRESC) {
prescaler = ADF4350_REG1_PRESCALER;
mdiv = 75;
}
else
{
prescaler = 0;
mdiv = 23;
}
st->r4_rf_div_sel = 0;
while (freq < ADF4350_MIN_VCO_FREQ)
{
freq <<= 1;
st->r4_rf_div_sel++;
}
/*
* Allow a predefined reference division factor
* if not set, compute our own
*/
if (pdata->ref_div_factor)
r_cnt = pdata->ref_div_factor - 1;
chspc = st->chspc;
do
{
do
{
do
{
r_cnt = adf4350_tune_r_cnt(st, r_cnt);
st->r1_mod = st->fpfd / chspc;
if (r_cnt > ADF4350_MAX_R_CNT)
{
/* try higher spacing values */
chspc++;
r_cnt = 0;
}
} while ((st->r1_mod > ADF4350_MAX_MODULUS) && r_cnt);
} while (r_cnt == 0);
tmp = freq * (uint64_t)st->r1_mod + (st->fpfd > 1);
tmp = (tmp / st->fpfd); /* Div round closest (n + d/2)/d */
st->r0_fract = tmp % st->r1_mod;
tmp = tmp / st->r1_mod;
st->r0_int = tmp;
} while (mdiv > st->r0_int);
band_sel_div = st->fpfd % ADF4350_MAX_BANDSEL_CLK > ADF4350_MAX_BANDSEL_CLK / 2 ?
st->fpfd / ADF4350_MAX_BANDSEL_CLK + 1 :
st->fpfd / ADF4350_MAX_BANDSEL_CLK;
if (st->r0_fract && st->r1_mod) {
div_gcd = gcd(st->r1_mod, st->r0_fract);
st->r1_mod /= div_gcd;
st->r0_fract /= div_gcd;
}
else
{
st->r0_fract = 0;
st->r1_mod = 1;
}
st->regs[ADF4350_REG0] = ADF4350_REG0_INT(st->r0_int) |
ADF4350_REG0_FRACT(st->r0_fract);
st->regs[ADF4350_REG1] = ADF4350_REG1_PHASE(1) |
ADF4350_REG1_MOD(st->r1_mod) |
prescaler;
st->regs[ADF4350_REG2] =
ADF4350_REG2_10BIT_R_CNT(r_cnt) |
ADF4350_REG2_DOUBLE_BUFF_EN |
(pdata->ref_doubler_en ? ADF4350_REG2_RMULT2_EN : 0) |
(pdata->ref_div2_en ? ADF4350_REG2_RDIV2_EN : 0) |
(pdata->r2_user_settings & (ADF4350_REG2_PD_POLARITY_POS |
ADF4350_REG2_LDP_6ns | ADF4350_REG2_LDF_INT_N |
ADF4350_REG2_CHARGE_PUMP_CURR_uA(5000) |
ADF4350_REG2_MUXOUT(0x7) | ADF4350_REG2_NOISE_MODE(0x9)));
st->regs[ADF4350_REG3] = pdata->r3_user_settings &
(ADF4350_REG3_12BIT_CLKDIV(0xFFF) |
ADF4350_REG3_12BIT_CLKDIV_MODE(0x3) |
ADF4350_REG3_12BIT_CSR_EN);
st->regs[ADF4350_REG4] =
ADF4350_REG4_FEEDBACK_FUND |
ADF4350_REG4_RF_DIV_SEL(st->r4_rf_div_sel) |
ADF4350_REG4_8BIT_BAND_SEL_CLKDIV(band_sel_div) |
ADF4350_REG4_RF_OUT_EN |
(pdata->r4_user_settings &
(ADF4350_REG4_OUTPUT_PWR(0x3) |
ADF4350_REG4_AUX_OUTPUT_PWR(0x3) |
ADF4350_REG4_AUX_OUTPUT_EN |
ADF4350_REG4_AUX_OUTPUT_FUND |
ADF4350_REG4_MUTE_TILL_LOCK_EN));
st->regs[ADF4350_REG5] = ADF4350_REG5_LD_PIN_MODE_DIGITAL | 0x00180000;
ret = adf4350_sync_config(st);
if(ret < 0)
{
return ret;
}
tmp = (uint64_t)((st->r0_int * st->r1_mod) + st->r0_fract) * (uint64_t)st->fpfd;
tmp = tmp / ((uint64_t)st->r1_mod * ((uint64_t)1 << st->r4_rf_div_sel));
return tmp;
}
/***************************************************************************//**
* @brief Initializes the ADF4350.
*
* @param spiBaseAddr - SPI peripheral AXI base address.
* @param ssNo - Slave select line on which the slave is connected.
*
* @return Returns 0 in case of success or negative error code.
*******************************************************************************/
int32_t adf4350_setup(uint32_t spi_device_id, uint8_t slave_select,
adf4350_init_param init_param)
{
struct adf4350_state *st = &adf4350_st;
adf4350_slave_select = slave_select;
SPISetupMode(spi_device_id,500000,0);//To CHeck last parameters : fixeme !
st->pdata = (struct adf4350_platform_data *)malloc(sizeof(*st->pdata));
if (!st->pdata)
return -1;
st->pdata->clkin = init_param.clkin;
st->pdata->channel_spacing = init_param.channel_spacing;
st->pdata->power_up_frequency = init_param.power_up_frequency;
st->pdata->ref_div_factor = init_param.reference_div_factor;
st->pdata->ref_doubler_en = init_param.reference_doubler_enable;
st->pdata->ref_div2_en = init_param.reference_div2_enable;
/* r2_user_settings */
st->pdata->r2_user_settings = init_param.phase_detector_polarity_positive_enable ?
ADF4350_REG2_PD_POLARITY_POS : 0;
st->pdata->r2_user_settings |= init_param.lock_detect_precision_6ns_enable ?
ADF4350_REG2_LDP_6ns : 0;
st->pdata->r2_user_settings |= init_param.lock_detect_function_integer_n_enable ?
ADF4350_REG2_LDF_INT_N : 0;
st->pdata->r2_user_settings |= ADF4350_REG2_CHARGE_PUMP_CURR_uA(init_param.charge_pump_current);
st->pdata->r2_user_settings |= ADF4350_REG2_MUXOUT(init_param.muxout_select);
st->pdata->r2_user_settings |= init_param.low_spur_mode_enable ? ADF4350_REG2_NOISE_MODE(0x3) : 0;
/* r3_user_settings */
st->pdata->r3_user_settings = init_param.cycle_slip_reduction_enable ?
ADF4350_REG3_12BIT_CSR_EN : 0;
st->pdata->r3_user_settings |= init_param.charge_cancellation_enable ?
ADF4351_REG3_CHARGE_CANCELLATION_EN : 0;
st->pdata->r3_user_settings |= init_param.anti_backlash_3ns_enable ?
ADF4351_REG3_ANTI_BACKLASH_3ns_EN : 0;
st->pdata->r3_user_settings |= init_param.band_select_clock_mode_high_enable ?
ADF4351_REG3_BAND_SEL_CLOCK_MODE_HIGH : 0;
st->pdata->r3_user_settings |= ADF4350_REG3_12BIT_CLKDIV(init_param.clk_divider_12bit);
st->pdata->r3_user_settings |= ADF4350_REG3_12BIT_CLKDIV_MODE(init_param.clk_divider_mode);
/* r4_user_settings */
st->pdata->r4_user_settings = init_param.aux_output_enable ?
ADF4350_REG4_AUX_OUTPUT_EN : 0;
st->pdata->r4_user_settings |= init_param.aux_output_fundamental_enable ?
ADF4350_REG4_AUX_OUTPUT_FUND : 0;
st->pdata->r4_user_settings |= init_param.mute_till_lock_enable ?
ADF4350_REG4_MUTE_TILL_LOCK_EN : 0;
st->pdata->r4_user_settings |= ADF4350_REG4_OUTPUT_PWR(init_param.output_power);
st->pdata->r4_user_settings |= ADF4350_REG4_AUX_OUTPUT_PWR(init_param.aux_output_power);
adf4350_out_altvoltage0_refin_frequency(st->pdata->clkin);
adf4350_out_altvoltage0_frequency_resolution(st->pdata->channel_spacing);
adf4350_out_altvoltage0_frequency(st->pdata->power_up_frequency);
printf("ADF4350 successfully initialized.\n");
/*int i;
for(i=0;i<6;i++)
printf("RegHw%d %x\n",i,st->regs[i]);
printf("Reg2 %x\n",st->pdata->r2_user_settings);
printf("Reg3 %x\n",st->pdata->r3_user_settings);
printf("Reg4 %x\n",st->pdata->r4_user_settings);*/
return 0;
}
/***************************************************************************//**
* @brief Stores PLL 0 frequency in Hz.
*
* @param Hz - The selected frequency.
*
* @return Returns the selected frequency.
*******************************************************************************/
int64_t adf4350_out_altvoltage0_frequency(int64_t Hz)
{
return adf4350_set_freq(&adf4350_st, Hz);
}
/***************************************************************************//**
* @brief Stores PLL 0 frequency resolution/channel spacing in Hz.
*
* @param Hz - The selected frequency.
*
* @return Returns the selected frequency.
*******************************************************************************/
int32_t adf4350_out_altvoltage0_frequency_resolution(int32_t Hz)
{
if(Hz != INT32_MAX)
{
adf4350_st.chspc = Hz;
}
return adf4350_st.chspc;
}
/***************************************************************************//**
* @brief Sets PLL 0 REFin frequency in Hz.
*
* @param Hz - The selected frequency.
*
* @return Returns the selected frequency.
*******************************************************************************/
int64_t adf4350_out_altvoltage0_refin_frequency(int64_t Hz)
{
if(Hz != INT32_MAX)
{
adf4350_st.clkin = Hz;
}
return adf4350_st.clkin;
}
/***************************************************************************//**
* @brief Powers down the PLL.
*
* @param pwd - Power option.
* Example: 0 - Power up the PLL.
* 1 - Power down the PLL.
*
* @return Returns the PLL's power status.
*******************************************************************************/
int32_t adf4350_out_altvoltage0_powerdown(int32_t pwd)
{
struct adf4350_state *st = &adf4350_st;
if(pwd == 1)
{
st->regs[ADF4350_REG2] |= ADF4350_REG2_POWER_DOWN_EN;
adf4350_sync_config(st);
}
if(pwd == 0)
{
st->regs[ADF4350_REG2] &= ~ADF4350_REG2_POWER_DOWN_EN;
adf4350_sync_config(st);
}
return (st->regs[ADF4350_REG2] & ADF4350_REG2_POWER_DOWN_EN);
}

Wyświetl plik

@ -0,0 +1,198 @@
/***************************************************************************//**
* @file adf4350.h
* @brief Header file of ADF4350 Driver.
* @author DBogdan (dragos.bogdan@analog.com)
********************************************************************************
* Copyright 2012-2015(c) Analog Devices, Inc.
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* - Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* - Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* - Neither the name of Analog Devices, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
* - The use of this software may or may not infringe the patent rights
* of one or more patent holders. This license does not release you
* from the requirement that you obtain separate licenses from these
* patent holders to use this software.
* - Use of the software either in source or binary form, must be run
* on or directly connected to an Analog Devices Inc. component.
*
* THIS SOFTWARE IS PROVIDED BY ANALOG DEVICES "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, NON-INFRINGEMENT,
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
* IN NO EVENT SHALL ANALOG DEVICES BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, INTELLECTUAL PROPERTY RIGHTS, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*******************************************************************************/
#ifndef __ADF4350_H__
#define __ADF4350_H__
/******************************************************************************/
/***************************** Include Files **********************************/
/******************************************************************************/
#include <stdint.h>
/******************************************************************************/
/********************** Macros and Constants Definitions **********************/
/******************************************************************************/
/* Channels */
#define ADF4350_RX_CHANNEL 0
#define ADF4350_TX_CHANNEL 1
/* Registers */
#define ADF4350_REG0 0
#define ADF4350_REG1 1
#define ADF4350_REG2 2
#define ADF4350_REG3 3
#define ADF4350_REG4 4
#define ADF4350_REG5 5
/* REG0 Bit Definitions */
#define ADF4350_REG0_FRACT(x) (((x) & 0xFFF) << 3)
#define ADF4350_REG0_INT(x) (((x) & 0xFFFF) << 15)
/* REG1 Bit Definitions */
#define ADF4350_REG1_MOD(x) (((x) & 0xFFF) << 3)
#define ADF4350_REG1_PHASE(x) (((x) & 0xFFF) << 15)
#define ADF4350_REG1_PRESCALER (1 << 27)
/* REG2 Bit Definitions */
#define ADF4350_REG2_COUNTER_RESET_EN (1 << 3)
#define ADF4350_REG2_CP_THREESTATE_EN (1 << 4)
#define ADF4350_REG2_POWER_DOWN_EN (1 << 5)
#define ADF4350_REG2_PD_POLARITY_POS (1 << 6)
#define ADF4350_REG2_LDP_6ns (1 << 7)
#define ADF4350_REG2_LDP_10ns (0 << 7)
#define ADF4350_REG2_LDF_FRACT_N (0 << 8)
#define ADF4350_REG2_LDF_INT_N (1 << 8)
#define ADF4350_REG2_CHARGE_PUMP_CURR_uA(x) (((((x)-312) / 312) & 0xF) << 9)
#define ADF4350_REG2_DOUBLE_BUFF_EN (1 << 13)
#define ADF4350_REG2_10BIT_R_CNT(x) ((x) << 14)
#define ADF4350_REG2_RDIV2_EN (1 << 24)
#define ADF4350_REG2_RMULT2_EN (1 << 25)
#define ADF4350_REG2_MUXOUT(x) ((x) << 26)
#define ADF4350_REG2_NOISE_MODE(x) ((x) << 29)
/* REG3 Bit Definitions */
#define ADF4350_REG3_12BIT_CLKDIV(x) ((x) << 3)
#define ADF4350_REG3_12BIT_CLKDIV_MODE(x) ((x) << 16)
#define ADF4350_REG3_12BIT_CSR_EN (1 << 18)
#define ADF4351_REG3_CHARGE_CANCELLATION_EN (1 << 21)
#define ADF4351_REG3_ANTI_BACKLASH_3ns_EN (1 << 22)
#define ADF4351_REG3_BAND_SEL_CLOCK_MODE_HIGH (1 << 23)
/* REG4 Bit Definitions */
#define ADF4350_REG4_OUTPUT_PWR(x) ((x) << 3)
#define ADF4350_REG4_RF_OUT_EN (1 << 5)
#define ADF4350_REG4_AUX_OUTPUT_PWR(x) ((x) << 6)
#define ADF4350_REG4_AUX_OUTPUT_EN (1 << 8)
#define ADF4350_REG4_AUX_OUTPUT_FUND (1 << 9)
#define ADF4350_REG4_AUX_OUTPUT_DIV (0 << 9)
#define ADF4350_REG4_MUTE_TILL_LOCK_EN (1 << 10)
#define ADF4350_REG4_VCO_PWRDOWN_EN (1 << 11)
#define ADF4350_REG4_8BIT_BAND_SEL_CLKDIV(x) ((x) << 12)
#define ADF4350_REG4_RF_DIV_SEL(x) ((x) << 20)
#define ADF4350_REG4_FEEDBACK_DIVIDED (0 << 23)
#define ADF4350_REG4_FEEDBACK_FUND (1 << 23)
/* REG5 Bit Definitions */
#define ADF4350_REG5_LD_PIN_MODE_LOW (0 << 22)
#define ADF4350_REG5_LD_PIN_MODE_DIGITAL (1 << 22)
#define ADF4350_REG5_LD_PIN_MODE_HIGH (3 << 22)
/* Specifications */
#define ADF4350_MAX_OUT_FREQ 4400000000ULL /* Hz */
#define ADF4350_MIN_OUT_FREQ 34375000 /* Hz */
#define ADF4350_MIN_VCO_FREQ 2200000000ULL /* Hz */
#define ADF4350_MAX_FREQ_45_PRESC 3000000000ULL /* Hz */
#define ADF4350_MAX_FREQ_PFD 32000000 /* Hz */
#define ADF4350_MAX_BANDSEL_CLK 125000 /* Hz */
#define ADF4350_MAX_FREQ_REFIN 250000000 /* Hz */
#define ADF4350_MAX_MODULUS 4095
#define ADF4350_MAX_R_CNT 1023
/******************************************************************************/
/************************ Types Definitions ***********************************/
/******************************************************************************/
struct adf4350_platform_data
{
uint32_t clkin;
uint32_t channel_spacing;
uint64_t power_up_frequency;
uint16_t ref_div_factor; /* 10-bit R counter */
uint8_t ref_doubler_en;
uint8_t ref_div2_en;
uint32_t r2_user_settings;
uint32_t r3_user_settings;
uint32_t r4_user_settings;
int32_t gpio_lock_detect;
};
typedef struct
{
uint32_t clkin;
uint32_t channel_spacing;
uint32_t power_up_frequency;
uint32_t reference_div_factor;
uint8_t reference_doubler_enable;
uint8_t reference_div2_enable;
/* r2_user_settings */
uint8_t phase_detector_polarity_positive_enable;
uint8_t lock_detect_precision_6ns_enable;
uint8_t lock_detect_function_integer_n_enable;
uint32_t charge_pump_current;
uint32_t muxout_select;
uint8_t low_spur_mode_enable;
/* r3_user_settings */
uint8_t cycle_slip_reduction_enable;
uint8_t charge_cancellation_enable;
uint8_t anti_backlash_3ns_enable;
uint8_t band_select_clock_mode_high_enable;
uint32_t clk_divider_12bit;
uint32_t clk_divider_mode;
/* r4_user_settings */
uint8_t aux_output_enable;
uint8_t aux_output_fundamental_enable;
uint8_t mute_till_lock_enable;
uint32_t output_power;
uint32_t aux_output_power;
}adf4350_init_param;
/******************************************************************************/
/************************ Functions Declarations ******************************/
/******************************************************************************/
/*! Initializes the ADF4350. */
int32_t adf4350_setup(uint32_t spi_device_id, uint8_t slave_select,
adf4350_init_param init_param);
/*! Writes 4 bytes of data to ADF4350. */
int32_t adf4350_write(uint32_t data);
/*! Stores PLL 0 frequency in Hz. */
int64_t adf4350_out_altvoltage0_frequency(int64_t Hz);
/*! Stores PLL 0 frequency resolution/channel spacing in Hz. */
int32_t adf4350_out_altvoltage0_frequency_resolution(int32_t Hz);
/*! Sets PLL 0 REFin frequency in Hz. */
int64_t adf4350_out_altvoltage0_refin_frequency(int64_t Hz);
/*! Powers down the PLL. */
int32_t adf4350_out_altvoltage0_powerdown(int32_t pwd);
#endif // __ADF4350_H__

Wyświetl plik

@ -0,0 +1,92 @@
#include <stdint.h>
#include <unistd.h>
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <getopt.h>
#include <fcntl.h>
#include <sys/ioctl.h>
#include <linux/types.h>
#include <linux/spi/spidev.h>
#include <wiringPi.h>
#include "adf4351.h"
adf4350_init_param MyAdf=
{.clkin=25000000,
.channel_spacing=5000,
.power_up_frequency=437000000,
.reference_div_factor=0,
.reference_doubler_enable=0,
.reference_div2_enable=0,
// r2_user_settings
.phase_detector_polarity_positive_enable=1,
.lock_detect_precision_6ns_enable=0,
.lock_detect_function_integer_n_enable=0,
.charge_pump_current=7, // FixMe
.muxout_select=0,
.low_spur_mode_enable=1,
// r3_user_settings
.cycle_slip_reduction_enable=1,
.charge_cancellation_enable=0,
.anti_backlash_3ns_enable=0,
.band_select_clock_mode_high_enable=1,
.clk_divider_12bit=0,
.clk_divider_mode=0,
// r4_user_settings
.aux_output_enable=1,
.aux_output_fundamental_enable=1,
.mute_till_lock_enable=0,
.output_power=0,//-4dbm
.aux_output_power=0
};
uint32_t registers[6] = {0x4580A8, 0x80080C9, 0x4E42, 0x4B3, 0xBC803C, 0x580005};
//REG 0
//REG1 1000000000001000000011001 001
//REG2 100111001000 010
//REG3 10010110 011
//REG4 101111001000000000111 100
/***************************************************************************//**
* @brief Powers off or sets the Synth frequency.
*
* @param "off" or freq in MHz (float).
*
* @return 0 or 1 if freq out of bounds
*******************************************************************************/
int main(int argc, char *argv[])
{
if (wiringPiSetup() == -1);
if (strcmp(argv[1], "off") == 0)
{
// Turn VCO Off and return
adf4350_out_altvoltage0_powerdown(1);
return 0;
}
else if ( atof(argv[1])>=35 && atof(argv[1])<=4400 )
{
// Valid freq, so set it
uint32_t adf4350_requested_frequency = 1000000 * atof(argv[1]);
adf4350_setup(0,0,MyAdf);
adf4350_out_altvoltage0_frequency(adf4350_requested_frequency);
return 0;
}
else
{
// Requested freq out of limits so print error and return 1
printf("ERROR: Requested Frequency out of limits");
return 1;
}
}