Commit 88d91d86 authored by Alessandro Rubini's avatar Alessandro Rubini

Merge branch 'verbosity-cleanup'

parents 45019e27 333c50bb
......@@ -26,6 +26,15 @@ config RAMSIZE
default 65536 if WR_SWITCH
default 131072
config PLL_VERBOSE
boolean
default y if WR_SWITCH
config WRC_VERBOSE
boolean
default y if WR_SWITCH
# CONFIG_WR_SWITCH has no further options at all at this point
config WR_NODE_PCS16
......@@ -230,6 +239,29 @@ config UART_SW
are routed to the software uart. The interactive wrpc shell
and diagnostics run on the hardware UART if available.
config NET_VERBOSE
depends on DEVELOPER && WR_NODE
boolean "Extra verbose messages for networking"
help
This is mainly a debug tool, to be left off unless you hack
in the network subsystem.
config PLL_VERBOSE
depends on DEVELOPER
boolean "Verbose messages in softpll"
help
The softpll is usually silent in WR node and verbose in WR
switch. You can enable pll messages in WR node for debugging.
config WRC_VERBOSE
depends on DEVELOPER
boolean "More verbose messages in wr core"
default y if WR_SWITCH
help
This enables some more diagnostic messages. Normally off.
config SDB_STORAGE
depends on WR_NODE
default y
......
......@@ -76,8 +76,6 @@ include softpll/softpll.mk
# ppsi already has div64 (the same one), so only pick it if not using ppsi.
ifndef CONFIG_PPSI
obj-y += pp_printf/div64.o
# unfortunately, we need a prototype therex
cflags-y += -include include/wrc.h
endif
# And always complain if we pick the libgcc division: 64/32 = 32 is enough here.
obj-y += check-error.o
......@@ -91,7 +89,7 @@ cflags-$(CONFIG_WR_NODE) += -Isdb-lib
CFLAGS = $(CFLAGS_PLATFORM) $(cflags-y) -Wall -Wstrict-prototypes \
-ffunction-sections -fdata-sections -Os -Wmissing-prototypes \
-include include/trace.h -ggdb
-include include/wrc.h -ggdb
LDFLAGS = $(LDFLAGS_PLATFORM) \
-Wl,--gc-sections -Os -lgcc -lc
......
......@@ -6,6 +6,8 @@ CONFIG_WR_NODE=y
CONFIG_PRINT_BUFSIZE=128
# CONFIG_PRINTF_XINT is not set
CONFIG_RAMSIZE=131072
CONFIG_PLL_VERBOSE=y
CONFIG_WRC_VERBOSE=y
# CONFIG_WR_NODE_PCS16 is not set
CONFIG_STACKSIZE=2048
CONFIG_PPSI=y
......@@ -26,6 +28,7 @@ CONFIG_PRINTF_FULL=y
# CONFIG_PRINTF_NONE is not set
CONFIG_DETERMINISTIC_BINARY=y
CONFIG_UART_SW=y
CONFIG_NET_VERBOSE=y
CONFIG_SDB_STORAGE=y
# CONFIG_LEGACY_EEPROM is not set
CONFIG_VLAN_ARRAY_SIZE=1
......@@ -169,7 +169,7 @@ static int ad9516_set_output_divider(int output, int ratio, int phase_offset)
uint16_t base = ((output - 6) / 2) * 0x5 + 0x199;
TRACE("Output [divider %d]: %d ratio: %d base %x lc %d hc %d\n", secondary, output, ratio, base, lcycles ,hcycles);
pp_printf("Output [divider %d]: %d ratio: %d base %x lc %d hc %d\n", secondary, output, ratio, base, lcycles ,hcycles);
if(!secondary)
{
......@@ -222,7 +222,7 @@ static void ad9516_sync_outputs(void)
int ad9516_init(int scb_version)
{
TRACE("Initializing AD9516 PLL...\n");
pp_printf("Initializing AD9516 PLL...\n");
oc_spi_init((void *)BASE_SPI);
......@@ -239,7 +239,7 @@ int ad9516_init(int scb_version)
/* Check the presence of the chip */
if (ad9516_read_reg(0x3) != 0xc3) {
TRACE("Error: AD9516 PLL not responding.\n");
pp_printf("Error: AD9516 PLL not responding.\n");
return -1;
}
......@@ -279,7 +279,7 @@ int ad9516_init(int scb_version)
ad9516_sync_outputs();
ad9516_set_vco_divider(3);
TRACE("AD9516 locked.\n");
pp_printf("AD9516 locked.\n");
gpio_out(GPIO_SYS_CLK_SEL, 1); /* switch the system clock to the PLL reference */
gpio_out(GPIO_PERIPH_RESET_N, 0); /* reset all peripherals which use AD9516-provided clocks */
......
......@@ -15,8 +15,7 @@
* the actual packet filter rules are created
*/
#include <stdio.h>
#include <wrc.h>
#include <endpoint.h>
#include <hw/endpoint_regs.h>
......
......@@ -361,7 +361,7 @@ int minic_tx_frame(uint8_t * hdr, uint8_t * payload, uint32_t size,
fid = MINIC_TSR0_FID_R(minic_readl(MINIC_REG_TSR0));
if (fid != WRPC_FID) {
TRACE_DEV("minic_tx_frame: unmatched fid %d vs %d\n",
wrc_verbose("minic_tx_frame: unmatched fid %d vs %d\n",
fid, WRPC_FID);
}
......@@ -376,7 +376,7 @@ int minic_tx_frame(uint8_t * hdr, uint8_t * payload, uint32_t size,
hwts->ahead = 0;
hwts->nsec = counter_r * (REF_CLOCK_PERIOD_PS / 1000);
// TRACE_DEV("minic_tx_frame [%d bytes] TS: %d.%d valid %d\n", size, hwts->utc, hwts->nsec, hwts->valid);
// wrc_verbose("minic_tx_frame [%d bytes] TS: %d.%d valid %d\n", size, hwts->utc, hwts->nsec, hwts->valid);
minic.tx_count++;
}
......
......@@ -45,7 +45,7 @@ void shw_pps_gen_init()
/* Adjusts the nanosecond (refclk cycle) counter by atomically adding (how_much) cycles. */
int shw_pps_gen_adjust(int counter, int64_t how_much)
{
TRACE_DEV("Adjust: counter = %s [%c%d]\n",
wrc_verbose("Adjust: counter = %s [%c%d]\n",
counter == PPSG_ADJUST_SEC ? "seconds" : "nanoseconds",
how_much < 0 ? '-' : '+', (int32_t) abs(how_much));
......
......@@ -12,7 +12,6 @@
#include <wrc.h>
#include "board.h"
#include "trace.h"
#include "syscon.h"
#include "endpoint.h"
#include "softpll_ng.h"
......@@ -150,7 +149,7 @@ int rxts_calibration_update(uint32_t *t24p_value)
if (cal_cur_phase >= CAL_SCAN_RANGE) {
if (det_rising.state != TD_DONE || det_falling.state != TD_DONE)
{
TRACE_DEV("RXTS calibration error.\n");
wrc_verbose("RXTS calibration error.\n");
return -1;
}
......@@ -173,7 +172,7 @@ int rxts_calibration_update(uint32_t *t24p_value)
if(ttrans >= REF_CLOCK_PERIOD_PS) ttrans -= REF_CLOCK_PERIOD_PS;
TRACE_DEV("RXTS calibration: R@%dps, F@%dps, transition@%dps\n",
wrc_verbose("RXTS calibration: R@%dps, F@%dps, transition@%dps\n",
det_rising.trans_phase, det_falling.trans_phase,
ttrans);
......
#ifndef __FREESTANDING_TRACE_H__
#define __FREESTANDING_TRACE_H__
#ifdef CONFIG_WR_NODE
#include <wrc.h>
#ifdef CONFIG_NET_VERBOSE
#define NET_IS_VERBOSE 1
#else
#define NET_IS_VERBOSE 0
#endif
#ifdef CONFIG_PLL_VERBOSE
#define PLL_IS_VERBOSE 1
#else
#define PLL_IS_VERBOSE 0
#endif
#define TRACE_WRAP(...)
#define TRACE_DEV(...) wrc_debug_printf(0, __VA_ARGS__)
#ifdef CONFIG_WRC_VERBOSE
#define WRC_IS_VERBOSE 1
#else
#define WRC_IS_VERBOSE 0
#endif
#else /* WR_SWITCH */
#define pll_verbose(...) \
({if (PLL_IS_VERBOSE) __debug_printf(__VA_ARGS__);})
#include <pp-printf.h>
#define TRACE(...) pp_printf(__VA_ARGS__)
#define TRACE_DEV(...) pp_printf(__VA_ARGS__)
#define wrc_verbose(...) \
({if (WRC_IS_VERBOSE) __debug_printf(__VA_ARGS__);})
#endif /* node/switch */
#define net_verbose(...) \
({if (NET_IS_VERBOSE) __debug_printf(__VA_ARGS__);})
#endif
#endif /* __FREESTANDING_TRACE_H__ */
......@@ -21,9 +21,11 @@ char *format_time(uint64_t sec);
/* Color printf() variant. */
void cprintf(int color, const char *fmt, ...);
/* Color printf() variant, sets curspor position to (row, col) before printing. */
/* Color printf() variant, sets curspor position to (row, col) too. */
void pcprintf(int row, int col, int color, const char *fmt, ...);
void __debug_printf(const char *fmt, ...);
/* Clears the terminal scree. */
void term_clear(void);
......
......@@ -15,6 +15,8 @@
#include <inttypes.h>
#include <syscon.h>
#include <pp-printf.h>
#include <util.h>
#include <trace.h>
#define vprintf pp_vprintf
#define sprintf pp_sprintf
......@@ -35,7 +37,6 @@
void wrc_mon_gui(void);
void shell_init(void);
int wrc_log_stats(void);
void wrc_debug_printf(int subsys, const char *fmt, ...);
/* This header is included by softpll: manage wrc/wrs difference */
#ifdef CONFIG_WR_NODE
......
......@@ -40,7 +40,7 @@ static void clear_state(void)
/* Sets the phase setpoint on a given channel */
int rts_adjust_phase(int channel, int32_t phase_setpoint)
{
// TRACE("Adjusting phase: ref channel %d, setpoint=%d ps.\n", channel, phase_setpoint);
// pp_printf("Adjusting phase: ref channel %d, setpoint=%d ps.\n", channel, phase_setpoint);
spll_set_phase_shift(0, phase_setpoint);
pstate.channels[channel].phase_setpoint = phase_setpoint;
return 0;
......@@ -69,7 +69,7 @@ int rts_set_mode(int mode)
for(i=0;options[i].desc != NULL;i++)
if(mode == options[i].mode_rt)
{
TRACE("RT: Setting mode to %s.\n", options[i].desc);
pp_printf("RT: Setting mode to %s.\n", options[i].desc);
if(options[i].do_init)
spll_init(options[i].mode_spll, 0, 1);
else
......@@ -84,12 +84,12 @@ int rts_lock_channel(int channel, int priority)
{
if(pstate.mode != RTS_MODE_BC)
{
TRACE("trying to lock while not in slave mode,..\n");
pp_printf("trying to lock while not in slave mode,..\n");
return -1;
}
TRACE("RT [slave]: Locking to: %d (prio %d)\n", channel, priority);
pp_printf("RT [slave]: Locking to: %d (prio %d)\n", channel, priority);
spll_init(SPLL_MODE_SLAVE, channel, 0);
pstate.current_ref = channel;
......
......@@ -11,6 +11,7 @@
#include <stdio.h>
#include <string.h>
#include <errno.h>
#include <stdarg.h>
#include "hal_exports.h"
#include <wrpc.h>
......@@ -60,7 +61,7 @@ int ptpd_netif_init()
return PTPD_NETIF_OK;
}
//#define TRACE_WRAP pp_printf
//#define net_verbose pp_printf
int ptpd_netif_get_hw_addr(wr_socket_t * sock, mac_addr_t * mac)
{
get_mac_addr((uint8_t *) mac);
......@@ -93,7 +94,7 @@ wr_socket_t *ptpd_netif_create_socket(int unused, int unusd2,
}
if (!sock) {
TRACE_WRAP("No sockets left.\n");
net_verbose("No sockets left.\n");
return NULL;
}
......@@ -128,9 +129,9 @@ int ptpd_netif_close_socket(wr_socket_t * sock)
/*
* The new, fully verified linearization algorithm.
* Merges the phase, measured by the DDMTD with the number of clock ticks,
* and makes sure there are no jumps resulting from different moments of transitions in the
* coarse counter and the phase values.
* Merges the phase, measured by the DDMTD with the number of clock
* ticks, and makes sure there are no jumps resulting from different
* moments of transitions in the coarse counter and the phase values.
* As a result, we get the full, sub-ns RX timestamp.
*
* Have a look at the note at http://ohwr.org/documents/xxx for details.
......@@ -143,50 +144,55 @@ void ptpd_netif_linearize_rx_timestamp(wr_timestamp_t * ts, int32_t dmtd_phase,
ts->raw_phase = dmtd_phase;
/* The idea is simple: the asynchronous RX timestamp trigger is tagged by two counters:
one counting at the rising clock edge, and the other on the falling. That means, the rising
timestamp is 180 degree in advance wrs to the falling one. */
/* The idea is simple: the asynchronous RX timestamp trigger is tagged
* by two counters: one counting at the rising clock edge, and the
* other on the falling. That means, the rising timestamp is 180
* degree in advance wrs to the falling one.
*/
/* Calculate the nanoseconds value for both timestamps. The rising edge one
is just the HW register */
nsec_r = ts->nsec;
/* The falling edge TS is the rising - 1 thick if the "rising counter ahead" bit is set. */
nsec_f = cntr_ahead ? ts->nsec - (clock_period / 1000) : ts->nsec;
nsec_r = ts->nsec;
/* The falling edge TS is the rising - 1 thick
if the "rising counter ahead" bit is set. */
nsec_f = cntr_ahead ? ts->nsec - (clock_period / 1000) : ts->nsec;
/* Adjust the rising edge timestamp phase so that it "jumps" roughly around the point
where the counter value changes */
/* Adjust the rising edge timestamp phase so that it "jumps" roughly
around the point where the counter value changes */
int phase_r = ts->raw_phase - transition_point;
if(phase_r < 0) /* unwrap negative value */
phase_r += clock_period;
/* Do the same with the phase for the falling edge, but additionally shift it by extra 180 degrees
(so that it matches the falling edge counter) */
/* Do the same with the phase for the falling edge, but additionally shift
it by extra 180 degrees (so that it matches the falling edge counter) */
int phase_f = ts->raw_phase - transition_point + (clock_period / 2);
if(phase_f < 0)
phase_f += clock_period;
if(phase_f >= clock_period)
phase_f -= clock_period;
/* If we are within +- 25% from the transition in the rising edge counter, pick the falling one */
if( phase_r > 3 * clock_period / 4 || phase_r < clock_period / 4 )
{
/* If we are within +- 25% from the transition in the rising edge counter,
pick the falling one */
if( phase_r > 3 * clock_period / 4 || phase_r < clock_period / 4 ) {
ts->nsec = nsec_f;
/* The falling edge timestamp is half a cycle later with respect to the rising one. Add
the extra delay, as rising edge is our reference */
/* The falling edge timestamp is half a cycle later
with respect to the rising one. Add
the extra delay, as rising edge is our reference */
ts->phase = phase_f + clock_period / 2;
if(ts->phase >= clock_period) /* Handle overflow */
{
ts->phase -= clock_period;
ts->nsec += (clock_period / 1000);
}
} else { /* We are closer to the falling edge counter transition? Pick the opposite timestamp */
} else { /* We are closer to the falling edge counter transition?
Pick the opposite timestamp */
ts->nsec = nsec_r;
ts->phase = phase_r;
}
/* In an unlikely case, after all the calculations, the ns counter may be overflown. */
/* In an unlikely case, after all the calculations,
the ns counter may be overflown. */
if(ts->nsec >= 1000000000)
{
ts->nsec -= 1000000000;
......@@ -201,7 +207,7 @@ static int wrap_copy_in(void *dst, struct sockq *q, size_t len)
char *dptr = dst;
int i = len;
TRACE_WRAP("copy_in: tail %d avail %d len %d\n", q->tail, q->avail,
net_verbose("copy_in: tail %d avail %d len %d\n", q->tail, q->avail,
len);
while (i--) {
......@@ -218,7 +224,7 @@ static int wrap_copy_out(struct sockq *q, void *src, size_t len)
char *sptr = src;
int i = len;
TRACE_WRAP("copy_out: head %d avail %d len %d\n", q->head, q->avail,
net_verbose("copy_out: head %d avail %d len %d\n", q->head, q->avail,
len);
while (i--) {
......@@ -273,14 +279,10 @@ int ptpd_netif_recvfrom(wr_socket_t * sock, wr_sockaddr_t * from, void *data,
REF_CLOCK_PERIOD_PS);
}
TRACE_WRAP("RX: Size %d tail %d Smac %x:%x:%x:%x:%x:%x\n", size,
net_verbose("RX: Size %d tail %d Smac %x:%x:%x:%x:%x:%x\n", size,
q->tail, hdr.srcmac[0], hdr.srcmac[1], hdr.srcmac[2],
hdr.srcmac[3], hdr.srcmac[4], hdr.srcmac[5]);
/* TRACE_WRAP("%s: received data from %02x:%02x:%02x:%02x:%02x:%02x to %02x:%02x:%02x:%02x:%02x:%02x\n", __FUNCTION__, from->mac[0],from->mac[1],from->mac[2],from->mac[3],
from->mac[4],from->mac[5],from->mac[6],from->mac[7],
from->mac_dest[0],from->mac_dest[1],from->mac_dest[2],from->mac_dest[3],
from->mac_dest[4],from->mac_dest[5],from->mac_dest[6],from->mac_dest[7]);*/
return min(size - sizeof(struct ethhdr), data_length);
}
......@@ -337,7 +339,7 @@ void update_rx_queues()
}
if (!s) {
TRACE_WRAP("%s: could not find socket for packet\n",
net_verbose("%s: could not find socket for packet\n",
__FUNCTION__);
return;
}
......@@ -347,7 +349,7 @@ void update_rx_queues()
sizeof(struct ethhdr) + recvd + sizeof(struct hw_timestamp) + 2;
if (q->avail < q_required) {
TRACE_WRAP
net_verbose
("%s: queue for socket full; [avail %d required %d]\n",
__FUNCTION__, q->avail, q_required);
return;
......@@ -361,10 +363,10 @@ void update_rx_queues()
q->avail -= wrap_copy_out(q, payload, size);
q->n++;
TRACE_WRAP("Q: Size %d head %d Smac %x:%x:%x:%x:%x:%x\n", recvd,
net_verbose("Q: Size %d head %d Smac %x:%x:%x:%x:%x:%x\n", recvd,
q->head, hdr.srcmac[0], hdr.srcmac[1], hdr.srcmac[2],
hdr.srcmac[3], hdr.srcmac[4], hdr.srcmac[5]);
TRACE_WRAP("%s: saved packet to queue [avail %d n %d size %d]\n",
net_verbose("%s: saved packet to queue [avail %d n %d size %d]\n",
__FUNCTION__, q->avail, q->n, q_required);
}
......@@ -12,8 +12,6 @@
#include <time.h>
#include <wrc.h>
#include "util.h"
/* cut from libc sources */
#define YEAR0 1900
......@@ -99,6 +97,15 @@ void pcprintf(int row, int col, int color, const char *fmt, ...)
pp_printf("\e[m");
}
void __debug_printf(const char *fmt, ...)
{
va_list ap;
va_start(ap, fmt);
vprintf(fmt, ap);
va_end(ap);
}
void term_clear(void)
{
pp_printf("\e[2J\e[1;1H");
......
......@@ -18,7 +18,6 @@
#include <syscon.h>
#include <pps_gen.h>
#include <onewire.h>
#include <util.h>
#include "wrc_ptp.h"
#include "hal_exports.h"
#include "lib/ipv4.h"
......
......@@ -14,7 +14,6 @@
#include <errno.h>
#include <wrc.h>
#include "util.h"
#include "uart.h"
#include "syscon.h"
#include "shell.h"
......
......@@ -13,7 +13,6 @@
#include <wrc.h>
#include "board.h"
#include "trace.h"
#include "hw/softpll_regs.h"
#include "hw/pps_gen_regs.h"
......@@ -347,12 +346,12 @@ void spll_init(int mode, int slave_ref_channel, int align_pps)
s->ext.main = &s->mpll;
external_init(&s->ext, spll_n_chan_ref + spll_n_chan_out, align_pps);
} else {
TRACE_DEV("softpll: attempting to enable GM mode on non-GM hardware.\n");
pll_verbose("softpll: attempting to enable GM mode on non-GM hardware.\n");
return;
}
}
TRACE_DEV
pll_verbose
("softpll: mode %s, %d ref channels, %d out channels\n",
modes[mode], spll_n_chan_ref, spll_n_chan_out);
......@@ -381,7 +380,7 @@ void spll_start_channel(int channel)
struct softpll_state *s = (struct softpll_state *) &softpll;
if (s->seq_state != SEQ_READY || !channel) {
TRACE_DEV("Can't start channel %d, the PLL is not ready\n",
pll_verbose("Can't start channel %d, the PLL is not ready\n",
channel);
return;
}
......@@ -502,13 +501,13 @@ void spll_enable_ptracker(int ref_channel, int enable)
ptracker_start((struct spll_ptracker_state *)&softpll.
ptrackers[ref_channel]);
ptracker_mask |= (1 << ref_channel);
TRACE_DEV("Enabling ptracker channel: %d\n", ref_channel);
pll_verbose("Enabling ptracker channel: %d\n", ref_channel);
} else {
ptracker_mask &= ~(1 << ref_channel);
if (ref_channel != softpll.mpll.id_ref)
spll_enable_tagger(ref_channel, 0);
TRACE_DEV("Disabling ptracker tagger: %d\n", ref_channel);
pll_verbose("Disabling ptracker tagger: %d\n", ref_channel);
}
}
......@@ -542,7 +541,7 @@ static int spll_update_aux_clocks(void)
if(s->seq_state != AUX_DISABLED && !aux_locking_enabled(ch))
{
TRACE_DEV("softpll: disabled aux channel %d\n", ch);
pll_verbose("softpll: disabled aux channel %d\n", ch);
spll_stop_channel(ch);
aux_set_channel_status(ch, 0);
s->seq_state = AUX_DISABLED;
......@@ -551,7 +550,7 @@ static int spll_update_aux_clocks(void)
switch (s->seq_state) {
case AUX_DISABLED:
if (softpll.mpll.ld.locked && aux_locking_enabled(ch)) {
TRACE_DEV("softpll: enabled aux channel %d\n", ch);
pll_verbose("softpll: enabled aux channel %d\n", ch);
spll_start_channel(ch);
s->seq_state = AUX_LOCK_PLL;
}
......@@ -559,7 +558,7 @@ static int spll_update_aux_clocks(void)
case AUX_LOCK_PLL:
if (s->pll.dmtd.ld.locked) {
TRACE_DEV ("softpll: channel %d locked [aligning @ %d ps]\n", ch, softpll.mpll_shift_ps);
pll_verbose ("softpll: channel %d locked [aligning @ %d ps]\n", ch, softpll.mpll_shift_ps);
set_phase_shift(ch, softpll.mpll_shift_ps);
s->seq_state = AUX_ALIGN_PHASE;
}
......@@ -568,7 +567,7 @@ static int spll_update_aux_clocks(void)
case AUX_ALIGN_PHASE:
if (!mpll_shifter_busy(&s->pll.dmtd)) {
TRACE_DEV("softpll: channel %d phase aligned\n", ch);
pll_verbose("softpll: channel %d phase aligned\n", ch);
aux_set_channel_status(ch, 1);
s->seq_state = AUX_READY;
}
......@@ -576,7 +575,7 @@ static int spll_update_aux_clocks(void)
case AUX_READY:
if (!softpll.mpll.ld.locked || !s->pll.dmtd.ld.locked) {
TRACE_DEV("softpll: aux channel %d or mpll lost lock\n", ch);
pll_verbose("softpll: aux channel %d or mpll lost lock\n", ch);
aux_set_channel_status(ch, 0);
s->seq_state = AUX_DISABLED;
}
......@@ -704,20 +703,20 @@ void check_vco_frequencies()
disable_irq();
int f_min, f_max;
TRACE_DEV("SoftPLL VCO Frequency/APR test:\n");
pll_verbose("SoftPLL VCO Frequency/APR test:\n");
spll_set_dac(-1, 0);
f_min = spll_measure_frequency(SPLL_OSC_DMTD);
spll_set_dac(-1, 65535);
f_max = spll_measure_frequency(SPLL_OSC_DMTD);
TRACE_DEV("DMTD VCO: Low=%d Hz Hi=%d Hz, APR = %d ppm.\n", f_min, f_max, calc_apr(f_min, f_max, 62500000));
pll_verbose("DMTD VCO: Low=%d Hz Hi=%d Hz, APR = %d ppm.\n", f_min, f_max, calc_apr(f_min, f_max, 62500000));
spll_set_dac(0, 0);
f_min = spll_measure_frequency(SPLL_OSC_REF);
spll_set_dac(0, 65535);
f_max = spll_measure_frequency(SPLL_OSC_REF);
TRACE_DEV("REF VCO: Low=%d Hz Hi=%d Hz, APR = %d ppm.\n", f_min, f_max, calc_apr(f_min, f_max, REF_CLOCK_FREQ_HZ));
pll_verbose("REF VCO: Low=%d Hz Hi=%d Hz, APR = %d ppm.\n", f_min, f_max, calc_apr(f_min, f_max, REF_CLOCK_FREQ_HZ));
f_min = spll_measure_frequency(SPLL_OSC_EXT);
TRACE_DEV("EXT clock: Freq=%d Hz\n", f_min);
pll_verbose("EXT clock: Freq=%d Hz\n", f_min);
}
......@@ -13,6 +13,7 @@
#define __SOFTPLL_NG_H
#include <stdint.h>
#include "util.h"
#include "spll_defs.h"
#include "spll_common.h"
#include "spll_debug.h"
......
......@@ -11,8 +11,7 @@
/* spll_common.c - common data structures and functions used by the SoftPLL */
#include <string.h>
#include <pp-printf.h>
#include "trace.h"
#include <wrc.h>
#include "softpll_ng.h"
int pi_update(spll_pi_t *pi, int x)
......@@ -127,7 +126,7 @@ Channels (spll_n_chan_ref ... spll_n_chan_out + spll_n_chan_ref-1) are the outpu
void spll_enable_tagger(int channel, int enable)
{
TRACE_DEV("EnableTagger %d %d\n", channel, enable);
pll_verbose("EnableTagger %d %d\n", channel, enable);
if (channel >= spll_n_chan_ref) { /* Output channel? */
if (enable)
SPLL->OCER |= 1 << (channel - spll_n_chan_ref);
......@@ -140,7 +139,7 @@ void spll_enable_tagger(int channel, int enable)
SPLL->RCER &= ~(1 << channel);
}
TRACE_DEV("%s: ch %d, OCER 0x%x, RCER 0x%x\n", __FUNCTION__, channel, SPLL->OCER, SPLL->RCER);
pll_verbose("%s: ch %d, OCER 0x%x, RCER 0x%x\n", __FUNCTION__, channel, SPLL->OCER, SPLL->RCER);
}
void biquad_init(spll_biquad_t *bq, const int *coefs, int shift)
......
......@@ -10,10 +10,8 @@
/* spll_external.h - implementation of SoftPLL servo for the
external (10 MHz - Grandmaster mode) reference channel */
#include <wrc.h>
#include "softpll_ng.h"
#include <pp-printf.h>
#include "trace.h"
#include "irq.h"
#define ALIGN_STATE_EXT_OFF 0
......@@ -135,7 +133,7 @@ void external_align_fsm(volatile struct spll_external_state *s)
PPSG->ADJ_NSEC = 3;
PPSG->ESCR = PPSG_ESCR_SYNC;
s->align_state = ALIGN_STATE_INIT_CSYNC;
TRACE_DEV("EXT: DMTD locked.\n");
pll_verbose("EXT: DMTD locked.\n");
}
break;
......@@ -151,7 +149,7 @@ void external_align_fsm(volatile struct spll_external_state *s)
if(time_after_eq(timer_get_tics(), s->align_timer)) {
s->align_state = ALIGN_STATE_START_ALIGNMENT;
s->align_shift = 0;
TRACE_DEV("EXT: CSync complete.\n");
pll_verbose("EXT: CSync complete.\n");
}
break;
......@@ -166,7 +164,7 @@ void external_align_fsm(volatile struct spll_external_state *s)
s->align_step = 100;
}
TRACE_DEV("EXT: Align target %d, step %d.\n", s->align_target, s->align_step);
pll_verbose("EXT: Align target %d, step %d.\n", s->align_target, s->align_step);
s->align_state = ALIGN_STATE_WAIT_SAMPLE;
}
break;
......@@ -187,7 +185,7 @@ void external_align_fsm(volatile struct spll_external_state *s)
case ALIGN_STATE_COMPENSATE_DELAY:
if(!mpll_shifter_busy(s->main)) {
TRACE_DEV("EXT: Align done.\n");
pll_verbose("EXT: Align done.\n");
s->align_state = ALIGN_STATE_LOCKED;
}
break;
......
......@@ -9,9 +9,8 @@
/* spll_main.c - Implementation of the main DDMTD PLL. */
#include <wrc.h>
#include "softpll_ng.h"
#include <pp-printf.h>
#include "trace.h"
#define MPLL_TAG_WRAPAROUND 100000000
......@@ -49,7 +48,7 @@ void mpll_init(struct spll_main_state *s, int id_ref,
s->id_out = id_out;
s->dac_index = id_out - spll_n_chan_ref;
TRACE_DEV("ref %d out %d idx %x \n", s->id_ref, s->id_out, s->dac_index);
pll_verbose("ref %d out %d idx %x \n", s->id_ref, s->id_out, s->dac_index);
pi_init((spll_pi_t *)&s->pi);
ld_init((spll_lock_det_t *)&s->ld);
......@@ -57,7 +56,7 @@ void mpll_init(struct spll_main_state *s, int id_ref,
void mpll_start(struct spll_main_state *s)
{
TRACE_DEV("MPLL_Start [dac %d]\n", s->dac_index);
pll_verbose("MPLL_Start [dac %d]\n", s->dac_index);
s->adder_ref = s->adder_out = 0;
s->tag_ref = -1;
......
......@@ -108,11 +108,11 @@ static int wrc_check_link(void)
int rv = 0;
if (!prev_link_state && link_state) {
TRACE_DEV("Link up.\n");
wrc_verbose("Link up.\n");
gpio_out(GPIO_LED_LINK, 1);
rv = LINK_WENT_UP;
} else if (prev_link_state && !link_state) {
TRACE_DEV("Link down.\n");
wrc_verbose("Link down.\n");
gpio_out(GPIO_LED_LINK, 0);
rv = LINK_WENT_DOWN;
} else
......@@ -122,21 +122,6 @@ static int wrc_check_link(void)
return rv;
}
void wrc_debug_printf(int subsys, const char *fmt, ...)
{
va_list ap;
if (wrc_ui_mode)
return;
va_start(ap, fmt);
if (subsys & (1 << 5) /* was: TRACE_SERVO -- see commit message */)
vprintf(fmt, ap);
va_end(ap);
}
int wrc_man_phase = 0;
static void ui_update(void)
......
......@@ -34,16 +34,16 @@ int main(void)
stats.start_cnt++;
_endram = ENDRAM_MAGIC;
uart_init_hw();
TRACE("\n");
TRACE("WR Switch Real Time Subsystem (c) CERN 2011 - 2014\n");
TRACE("Revision: %s, built: %s %s.\n",
pp_printf("\n");
pp_printf("WR Switch Real Time Subsystem (c) CERN 2011 - 2014\n");
pp_printf("Revision: %s, built: %s %s.\n",
build_revision, build_date, build_time);
TRACE("SCB version: %d. %s\n", scb_ver,(scb_ver>=34)?"10 MHz SMC Output.":"" );
TRACE("Start counter %d\n", stats.start_cnt);
TRACE("--\n");
pp_printf("SCB version: %d. %s\n", scb_ver,(scb_ver>=34)?"10 MHz SMC Output.":"" );
pp_printf("Start counter %d\n", stats.start_cnt);
pp_printf("--\n");
if (stats.start_cnt > 1) {
TRACE("!!spll does not work after restart!!\n");
pp_printf("!!spll does not work after restart!!\n");
/* for sure problem is in calling second time ad9516_init,
* but not only */
}
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment