New upstream version 0.0.0.73~rc1

This commit is contained in:
Hibby 2024-10-29 22:45:21 +00:00
parent b1d1488de6
commit d0709a1e0a
37 changed files with 7217 additions and 5615 deletions

377
6pack.cpp Normal file
View File

@ -0,0 +1,377 @@
/*
Using code from 6pack Linux Kernel driver with the following licence and credits
* 6pack driver version 0.4.2, 1999/08/22
*
* This module:
* This module 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 of the License, or (at your option) any later version.
*
* This module implements the AX.25 protocol for kernel-based
* devices like TTYs. It interfaces between a raw TTY, and the
* kernel's AX.25 protocol layers, just like slip.c.
* AX.25 needs to be separated from slip.c while slip.c is no
* longer a static kernel device since it is a module.
*
* Author: Andreas Könsgen <ajk@ccac.rwth-aachen.de>
*
* Lots of stuff has been taken from mkiss.c, written by
* Hans Alblas <hans@esrac.ele.tue.nl>
*
* with the fixes from
*
* Jonathan (G4KLX) Fixed to match Linux networking changes - 2.1.15.
* Matthias (DG2FEF) Fixed bug in ax25_close(): dev_lock_wait() was
* called twice, causing a deadlock.
*/
// 6pack needs fast response to received characters, and I want to be able to operate over TCP links as well as serial.
// So I think the character level stuff may need to run in a separate thread, probably using select.
//
// I also need to support multiple 6pack ports.
// ?? Do we add this as a backend to KISS driver or a separate Driver. KISS Driver is already quite messy. Not decided yet.
// ?? If using serial/real TNC we need to be able to interleave control and data bytes, but I think with TCP/QtSM it won't be necessary
// ?? Also a don't see any point in running multiple copies of QtSM on one port, but maybe should treat the QtSM channels as
// multidropped ports for scheduling (?? only if on same radio ??)
// ?? I think it needs to look like a KISS (L2) driver but will need a transmit scheduler level to do DCD/CSMA/PTT processing,
// ideally with an interlock to other drivers on same port. This needs some thought with QtSM KISS with multiple modems on one channel
#define WIN32_LEAN_AND_MEAN // Exclude rarely-used stuff from Windows headers
#define _CRT_SECURE_NO_DEPRECATE
/****************************************************************************
* Defines for the 6pack driver.
****************************************************************************/
#define TRUE 1
#define FALSE 0
#define AX25_MAXDEV 16 /* MAX number of AX25 channels;
This can be overridden with
insmod -oax25_maxdev=nnn */
#define AX_MTU 236
/* 6pack protocol bytes/masks. */
#define SIXP_INIT_CMD 0xE8
#define SIXP_TNC_FOUND 0xE9
#define SIXP_CMD_MASK 0xC0
#define SIXP_PRIO_CMD_MASK 0x80
#define SIXP_PRIO_DATA_MASK 0x38
#define SIXP_STD_CMD_MASK 0x40
#define SIXP_DCD_MASK 0x08
#define SIXP_RX_DCD_MASK 0x18
#define SIXP_CHN_MASK 0x07
#define SIXP_TX_MASK 0x20
#define SIXP_CON_LED_ON 0x68
#define SIXP_STA_LED_ON 0x70
#define SIXP_LED_OFF 0x60
/* checksum for a valid 6pack encapsulated packet */
#define SIXP_CHKSUM 0xFF
/* priority commands */
#define SIXP_SEOF 0x40 /* TX underrun */
#define SIXP_TX_URUN 0x48 /* TX underrun */
#define SIXP_RX_ORUN 0x50 /* RX overrun */
#define SIXP_RX_BUF_OVL 0x58 /* RX overrun */
struct ax_disp {
int magic;
char * name;
/* Various fields. */
// struct tty_struct *tty; /* ptr to TTY structure */
// struct device *dev; /* easy for intr handling */
struct ax_disp *sixpack; /* mkiss txport if mkiss channel*/
/* These are pointers to the malloc()ed frame buffers. */
unsigned char *rbuff; /* receiver buffer */
int rcount; /* received chars counter */
unsigned char *xbuff; /* transmitter buffer */
unsigned char *xhead; /* pointer to next byte to XMIT */
int xleft; /* bytes left in XMIT queue */
/* SLIP interface statistics. */
unsigned long rx_packets; /* inbound frames counter */
unsigned long tx_packets; /* outbound frames counter */
unsigned long rx_errors; /* Parity, etc. errors */
unsigned long tx_errors; /* Planned stuff */
unsigned long rx_dropped; /* No memory for skb */
unsigned long tx_dropped; /* When MTU change */
unsigned long rx_over_errors; /* Frame bigger then SLIP buf. */
/* Detailed SLIP statistics. */
int mtu; /* Our mtu (to spot changes!) */
int buffsize; /* Max buffers sizes */
unsigned char flags; /* Flag values/ mode etc */
#define AXF_INUSE 0 /* Channel in use */
#define AXF_ESCAPE 1 /* ESC received */
#define AXF_ERROR 2 /* Parity, etc. error */
#define AXF_KEEPTEST 3 /* Keepalive test flag */
#define AXF_OUTWAIT 4 /* is outpacket was flag */
int mode;
/* variables for the state machine */
unsigned char tnc_ok;
unsigned char status;
unsigned char status1;
unsigned char status2;
unsigned char duplex;
unsigned char led_state;
unsigned char tx_enable;
unsigned char raw_buf[4]; /* receive buffer */
unsigned char cooked_buf[400]; /* receive buffer after 6pack decoding */
unsigned int rx_count; /* counter for receive buffer */
unsigned int rx_count_cooked; /* counter for receive buffer after 6pack decoding */
unsigned char tx_delay;
unsigned char persistance;
unsigned char slottime;
};
struct sixpack_channel {
int magic; /* magic word */
int init; /* channel exists? */
struct tty_struct *tty; /* link to tty control structure */
};
#define AX25_MAGIC 0x5316
#define SIXP_DRIVER_MAGIC 0x5304
#define SIXP_INIT_RESYNC_TIMEOUT 150 /* in 10 ms */
#define SIXP_RESYNC_TIMEOUT 500 /* in 10 ms */
/* default radio channel access parameters */
#define SIXP_TXDELAY 25 /* in 10 ms */
#define SIXP_PERSIST 50
#define SIXP_SLOTTIME 10 /* in 10 ms */
static int sixpack_encaps(unsigned char *tx_buf, unsigned char *tx_buf_raw, int length, unsigned char tx_delay);
static void sixpack_decaps(struct ax_disp *, unsigned char);
static void decode_prio_command(unsigned char, struct ax_disp *);
static void decode_std_command(unsigned char, struct ax_disp *);
static void decode_data(unsigned char, struct ax_disp *);
static void resync_tnc(unsigned long);
static void xmit_on_air(struct ax_disp *ax);
static void start_tx_timer(struct ax_disp *ax);
extern "C" void Debugprintf(const char * format, ...);
void Process6PackByte(unsigned char inbyte);
struct ax_disp axdisp;
/* Send one completely decapsulated AX.25 packet to the AX.25 layer. */
static void ax_bump(struct ax_disp *ax)
{
}
void Process6PackData(unsigned char * Bytes, int Len)
{
while(Len--)
Process6PackByte(Bytes++[0]);
}
void Process6PackByte(unsigned char inbyte)
{
struct ax_disp *ax = &axdisp;
if (inbyte == SIXP_INIT_CMD)
{
Debugprintf("6pack: SIXP_INIT_CMD received.\n");
{
// Reset state machine and allocate a 6pack struct for each modem.
// reply with INIT_CMD with the channel no of last modem
}
return;
}
if ((inbyte & SIXP_PRIO_CMD_MASK) != 0)
decode_prio_command(inbyte, ax);
else if ((inbyte & SIXP_STD_CMD_MASK) != 0)
decode_std_command(inbyte, ax);
else {
if ((ax->status & SIXP_RX_DCD_MASK) == SIXP_RX_DCD_MASK)
decode_data(inbyte, ax);
} /* else */
}
/* identify and execute a 6pack priority command byte */
void decode_prio_command(unsigned char cmd, struct ax_disp *ax)
{
unsigned char channel;
channel = cmd & SIXP_CHN_MASK;
if ((cmd & SIXP_PRIO_DATA_MASK) != 0) { /* idle ? */
/* RX and DCD flags can only be set in the same prio command,
if the DCD flag has been set without the RX flag in the previous
prio command. If DCD has not been set before, something in the
transmission has gone wrong. In this case, RX and DCD are
cleared in order to prevent the decode_data routine from
reading further data that might be corrupt. */
if (((ax->status & SIXP_DCD_MASK) == 0) &&
((cmd & SIXP_RX_DCD_MASK) == SIXP_RX_DCD_MASK)) {
if (ax->status != 1)
Debugprintf("6pack: protocol violation\n");
else
ax->status = 0;
cmd &= !SIXP_RX_DCD_MASK;
}
ax->status = cmd & SIXP_PRIO_DATA_MASK;
} /* if */
/* if the state byte has been received, the TNC is present,
so the resync timer can be reset. */
if (ax->tnc_ok == 1) {
// del_timer(&(ax->resync_t));
// ax->resync_t.data = (unsigned long) ax;
// ax->resync_t.function = resync_tnc;
// ax->resync_t.expires = jiffies + SIXP_INIT_RESYNC_TIMEOUT;
// add_timer(&(ax->resync_t));
}
ax->status1 = cmd & SIXP_PRIO_DATA_MASK;
}
/* try to resync the TNC. Called by the resync timer defined in
decode_prio_command */
static void
resync_tnc(unsigned long channel)
{
static char resync_cmd = SIXP_INIT_CMD;
struct ax_disp *ax = (struct ax_disp *) channel;
Debugprintf("6pack: resyncing TNC\n");
/* clear any data that might have been received */
ax->rx_count = 0;
ax->rx_count_cooked = 0;
/* reset state machine */
ax->status = 1;
ax->status1 = 1;
ax->status2 = 0;
ax->tnc_ok = 0;
/* resync the TNC */
ax->led_state = SIXP_LED_OFF;
// ax->tty->driver.write(ax->tty, 0, &(ax->led_state), 1);
// ax->tty->driver.write(ax->tty, 0, &resync_cmd, 1);
/* Start resync timer again -- the TNC might be still absent */
// del_timer(&(ax->resync_t));
// ax->resync_t.data = (unsigned long) ax;
// ax->resync_t.function = resync_tnc;
// ax->resync_t.expires = jiffies + SIXP_RESYNC_TIMEOUT;
// add_timer(&(ax->resync_t));
}
/* identify and execute a standard 6pack command byte */
void decode_std_command(unsigned char cmd, struct ax_disp *ax)
{
unsigned char checksum = 0, channel;
unsigned int i;
channel = cmd & SIXP_CHN_MASK;
switch (cmd & SIXP_CMD_MASK) { /* normal command */
case SIXP_SEOF:
if ((ax->rx_count == 0) && (ax->rx_count_cooked == 0)) {
if ((ax->status & SIXP_RX_DCD_MASK) ==
SIXP_RX_DCD_MASK) {
ax->led_state = SIXP_CON_LED_ON;
// ax->tty->driver.write(ax->tty, 0, &(ax->led_state), 1);
} /* if */
}
else {
ax->led_state = SIXP_LED_OFF;
// ax->tty->driver.write(ax->tty, 0, &(ax->led_state), 1);
/* fill trailing bytes with zeroes */
if (ax->rx_count == 2) {
decode_data(0, ax);
decode_data(0, ax);
ax->rx_count_cooked -= 2;
}
else if (ax->rx_count == 3) {
decode_data(0, ax);
ax->rx_count_cooked -= 1;
}
for (i = 0; i < ax->rx_count_cooked; i++)
checksum += ax->cooked_buf[i];
if (checksum != SIXP_CHKSUM) {
Debugprintf("6pack: bad checksum %2.2x\n", checksum);
}
else {
ax->rcount = ax->rx_count_cooked - 1;
ax_bump(ax);
} /* else */
ax->rx_count_cooked = 0;
} /* else */
break;
case SIXP_TX_URUN:
Debugprintf("6pack: TX underrun\n");
break;
case SIXP_RX_ORUN:
Debugprintf("6pack: RX overrun\n");
break;
case SIXP_RX_BUF_OVL:
Debugprintf("6pack: RX buffer overflow\n");
} /* switch */
} /* function */
/* decode 4 sixpack-encoded bytes into 3 data bytes */
void decode_data(unsigned char inbyte, struct ax_disp *ax)
{
unsigned char *buf;
if (ax->rx_count != 3)
ax->raw_buf[ax->rx_count++] = inbyte;
else {
buf = ax->raw_buf;
ax->cooked_buf[ax->rx_count_cooked++] =
buf[0] | ((buf[1] << 2) & 0xc0);
ax->cooked_buf[ax->rx_count_cooked++] =
(buf[1] & 0x0f) | ((buf[2] << 2) & 0xf0);
ax->cooked_buf[ax->rx_count_cooked++] =
(buf[2] & 0x03) | (inbyte << 2);
ax->rx_count = 0;
}
}

View File

@ -1789,32 +1789,6 @@ int gpioInitialise(void)
int stricmp(const unsigned char * pStr1, const unsigned char *pStr2)
{
unsigned char c1, c2;
int v;
if (pStr1 == NULL)
{
if (pStr2)
Debugprintf("stricmp called with NULL 1st param - 2nd %s ", pStr2);
else
Debugprintf("stricmp called with two NULL params");
return 1;
}
do {
c1 = *pStr1++;
c2 = *pStr2++;
/* The casts are necessary when pStr1 is shorter & char is signed */
v = tolower(c1) - tolower(c2);
} while ((v == 0) && (c1 != '\0') && (c2 != '\0') );
return v;
}
char Leds[8]= {0}; char Leds[8]= {0};
unsigned int PKTLEDTimer = 0; unsigned int PKTLEDTimer = 0;
@ -2107,5 +2081,63 @@ int gethints()
return 0; return 0;
} }
// Microsoft routines not available in gcc
int memicmp(unsigned char *a, unsigned char *b, int n)
{
if (n)
{
while (n && (toupper(*a) == toupper(*b)))
n--, a++, b++;
if (n)
return toupper(*a) - toupper(*b);
}
return 0;
}
int stricmp(const unsigned char * pStr1, const unsigned char *pStr2)
{
unsigned char c1, c2;
int v;
if (pStr1 == NULL)
{
if (pStr2)
Debugprintf("stricmp called with NULL 1st param - 2nd %s ", pStr2);
else
Debugprintf("stricmp called with two NULL params");
return 1;
}
do {
c1 = *pStr1++;
c2 = *pStr2++;
/* The casts are necessary when pStr1 is shorter & char is signed */
v = tolower(c1) - tolower(c2);
} while ((v == 0) && (c1 != '\0') && (c2 != '\0'));
return v;
}
char * strupr(char* s)
{
char* p = s;
if (s == 0)
return 0;
while (*p = toupper(*p)) p++;
return s;
}
char * strlwr(char* s)
{
char* p = s;
while (*p = tolower(*p)) p++;
return s;
}

View File

@ -45,156 +45,28 @@ VOID ClearBusy()
intLastStop = 0; // This will force the busy detector to ignore old averages and initialze the rolling average filters intLastStop = 0; // This will force the busy detector to ignore old averages and initialze the rolling average filters
} }
/* extern int FFTSize;
// Function to implement a busy detector based on 1024 point FFT
BOOL BusyDetect2(float * dblMag, int intStart, int intStop) // this only called while searching for leader ...once leader detected, no longer called. BOOL BusyDetect3(float * dblMag, int StartFreq, int EndFreq)
{ {
// each bin is about 12000/1024 or 11.72 Hz
// this only called while searching for leader ...once leader detected, no longer called. // Based on code from ARDOP, but using diffferent FFT size
// QtSM is using an FFT size based on waterfall settings.
// First sort signals and look at highes signals:baseline ratio.. // First sort signals and look at highes signals:baseline ratio..
float dblAVGSignalPerBinNarrow, dblAVGSignalPerBinWide, dblAVGBaselineNarrow, dblAVGBaselineWide;
float dblFastAlpha = 0.4f;
float dblSlowAlpha = 0.2f;
float dblAvgStoNNarrow, dblAvgStoNWide;
int intNarrow = 8; // 8 x 11.72 Hz about 94 z
int intWide = ((intStop - intStart) * 2) / 3; //* 0.66);
int blnBusy = FALSE;
float dblAvgStoNSlowNarrow = 0;
float dblAvgStoNFastNarrow = 0;
float dblAvgStoNSlowWide = 0;
float dblAvgStoNFastWide = 0;
// First narrow band (~94Hz)
SortSignals(dblMag, intStart, intStop, intNarrow, &dblAVGSignalPerBinNarrow, &dblAVGBaselineNarrow);
if (intLastStart == intStart && intLastStop == intStop)
{
dblAvgStoNSlowNarrow = (1 - dblSlowAlpha) * dblAvgStoNSlowNarrow + dblSlowAlpha * dblAVGSignalPerBinNarrow / dblAVGBaselineNarrow;
dblAvgStoNFastNarrow = (1 - dblFastAlpha) * dblAvgStoNFastNarrow + dblFastAlpha * dblAVGSignalPerBinNarrow / dblAVGBaselineNarrow;
}
else
{
dblAvgStoNSlowNarrow = dblAVGSignalPerBinNarrow / dblAVGBaselineNarrow;
dblAvgStoNFastNarrow = dblAVGSignalPerBinNarrow / dblAVGBaselineNarrow;
intLastStart = intStart;
intLastStop = intStop;
}
dblAvgStoNNarrow = max(dblAvgStoNSlowNarrow, dblAvgStoNFastNarrow); // computes fast attack, slow release // Start and Stop are in Hz. Convert to bin numbers
// Wide band (66% ofr current bandwidth)
SortSignals(dblMag, intStart, intStop, intWide, &dblAVGSignalPerBinWide, &dblAVGBaselineWide);
if (intLastStart == intStart && intLastStop == intStop)
{
dblAvgStoNSlowWide = (1 - dblSlowAlpha) * dblAvgStoNSlowWide + dblSlowAlpha * dblAVGSignalPerBinWide / dblAVGBaselineWide;
dblAvgStoNFastWide = (1 - dblFastAlpha) * dblAvgStoNFastWide + dblFastAlpha * dblAVGSignalPerBinWide / dblAVGBaselineWide;
}
else
{
dblAvgStoNSlowWide = dblAVGSignalPerBinWide / dblAVGBaselineWide;
dblAvgStoNFastWide = dblAVGSignalPerBinWide / dblAVGBaselineWide;
intLastStart = intStart;
intLastStop = intStop;
}
dblAvgStoNNarrow = max(dblAvgStoNSlowNarrow, dblAvgStoNFastNarrow); // computes fast attack, slow release
dblAvgStoNWide = max(dblAvgStoNSlowWide, dblAvgStoNFastWide); // computes fast attack, slow release
// Preliminary calibration...future a function of bandwidth and BusyDet.
switch (ARQBandwidth)
{
case B200MAX:
case B200FORCED:
if (dblAvgStoNNarrow > 1.5 * BusyDet|| dblAvgStoNWide > 2.5 * BusyDet)
blnBusy = True;
break;
case B500MAX:
case B500FORCED:
if (dblAvgStoNNarrow > 1.5 * BusyDet || dblAvgStoNWide > 2.5 * BusyDet)
blnBusy = True;
break;
case B1000MAX:
case B1000FORCED:
if (dblAvgStoNNarrow > 1.4 * BusyDet || dblAvgStoNWide > 2 * BusyDet)
blnBusy = True;
break;
case B2000MAX:
case B2000FORCED:
if (dblAvgStoNNarrow > 1.4 * BusyDet || dblAvgStoNWide > 2 * BusyDet)
blnBusy = True;
}
if (blnBusy) // This used to skip over one call busy nuisance trips. Busy must be present at least 2 consecutive times to be reported
{
intBusyOnCnt += 1;
intBusyOffCnt = 0;
if (intBusyOnCnt > 1)
blnBusy = True;
else if (!blnBusy)
{
intBusyOffCnt += 1;
intBusyOnCnt = 0;
if (intBusyOffCnt > 3)
blnBusy = False;
}
}
if (blnLastBusy == False && blnBusy)
{
int x = round(dblAvgStoNNarrow); // odd, but PI doesnt print floats properly
int y = round(dblAvgStoNWide);
blnLastBusy = True;
LastBusyOn = Now;
#ifdef __ARM_ARCH
WriteDebugLog(LOGDEBUG, "[BusyDetect2: BUSY ON StoN Narrow = %d StoN Wide %d", x, y);
#else
WriteDebugLog(LOGDEBUG, "[BusyDetect2: BUSY ON StoN Narrow = %f StoN Wide %f", dblAvgStoNNarrow, dblAvgStoNWide);
#endif
}
else if (blnLastBusy == True && !blnBusy)
{
int x = round(dblAvgStoNNarrow); // odd, but PI doesnt print floats properly
int y = round(dblAvgStoNWide);
blnLastBusy = False;
LastBusyOff = Now;
#ifdef __ARM_ARCH
WriteDebugLog(LOGDEBUG, "[BusyDetect2: BUSY OFF StoN Narrow = %d StoN Wide %d", x, y);
#else
WriteDebugLog(LOGDEBUG, "[BusyDetect2: BUSY OFF StoN Narrow = %f StoN Wide %f", dblAvgStoNNarrow, dblAvgStoNWide);
#endif
}
return blnLastBusy;
}
*/ float BinSize = 12000.0 / FFTSize;
int StartBin = StartFreq / BinSize;
int EndBin = EndFreq / BinSize;
BOOL BusyDetect3(float * dblMag, int intStart, int intStop) // this only called while searching for leader ...once leader detected, no longer called.
{
// each bin is about 12000/1024 or 11.72 Hz
// this only called while searching for leader ...once leader detected, no longer called.
// First sort signals and look at highes signals:baseline ratio..
float dblAVGSignalPerBinNarrow, dblAVGSignalPerBinWide, dblAVGBaselineNarrow, dblAVGBaselineWide; float dblAVGSignalPerBinNarrow, dblAVGSignalPerBinWide, dblAVGBaselineNarrow, dblAVGBaselineWide;
float dblSlowAlpha = 0.2f; float dblSlowAlpha = 0.2f;
float dblAvgStoNNarrow = 0, dblAvgStoNWide = 0; float dblAvgStoNNarrow = 0, dblAvgStoNWide = 0;
int intNarrow = 8; // 8 x 11.72 Hz about 94 z int intNarrow = 100 / BinSize; // 8 x 11.72 Hz about 94 z
int intWide = ((intStop - intStart) * 2) / 3; //* 0.66); int intWide = ((EndBin - StartBin) * 2) / 3; //* 0.66);
int blnBusy = FALSE; int blnBusy = FALSE;
int BusyDet4th = BusyDet * BusyDet * BusyDet * BusyDet; int BusyDet4th = BusyDet * BusyDet * BusyDet * BusyDet;
@ -202,32 +74,32 @@ BOOL BusyDetect3(float * dblMag, int intStart, int intStop) // this only
// First sort signals and look at highest signals:baseline ratio.. // First sort signals and look at highest signals:baseline ratio..
// First narrow band (~94Hz) // First narrow band (~94Hz)
SortSignals2(dblMag, intStart, intStop, intNarrow, &dblAVGSignalPerBinNarrow, &dblAVGBaselineNarrow); SortSignals2(dblMag, StartBin, EndBin, intNarrow, &dblAVGSignalPerBinNarrow, &dblAVGBaselineNarrow);
if (intLastStart == intStart && intLastStop == intStop) if (intLastStart == StartBin && intLastStop == EndBin)
dblAvgStoNNarrow = (1 - dblSlowAlpha) * dblAvgStoNNarrow + dblSlowAlpha * dblAVGSignalPerBinNarrow / dblAVGBaselineNarrow; dblAvgStoNNarrow = (1 - dblSlowAlpha) * dblAvgStoNNarrow + dblSlowAlpha * dblAVGSignalPerBinNarrow / dblAVGBaselineNarrow;
else else
{ {
// This initializes the Narrow average after a bandwidth change // This initializes the Narrow average after a bandwidth change
dblAvgStoNNarrow = dblAVGSignalPerBinNarrow / dblAVGBaselineNarrow; dblAvgStoNNarrow = dblAVGSignalPerBinNarrow / dblAVGBaselineNarrow;
intLastStart = intStart; intLastStart = StartBin;
intLastStop = intStop; intLastStop = EndBin;
} }
// Wide band (66% of current bandwidth) // Wide band (66% of current bandwidth)
SortSignals2(dblMag, intStart, intStop, intWide, &dblAVGSignalPerBinWide, &dblAVGBaselineWide); SortSignals2(dblMag, StartBin, EndBin, intWide, &dblAVGSignalPerBinWide, &dblAVGBaselineWide);
if (intLastStart == intStart && intLastStop == intStop) if (intLastStart == StartBin && intLastStop == EndBin)
dblAvgStoNWide = (1 - dblSlowAlpha) * dblAvgStoNWide + dblSlowAlpha * dblAVGSignalPerBinWide / dblAVGBaselineWide; dblAvgStoNWide = (1 - dblSlowAlpha) * dblAvgStoNWide + dblSlowAlpha * dblAVGSignalPerBinWide / dblAVGBaselineWide;
else else
{ {
// This initializes the Wide average after a bandwidth change // This initializes the Wide average after a bandwidth change
dblAvgStoNWide = dblAVGSignalPerBinWide / dblAVGBaselineWide; dblAvgStoNWide = dblAVGSignalPerBinWide / dblAVGBaselineWide;
intLastStart = intStart; intLastStart = StartBin;
intLastStop = intStop; intLastStop = EndBin;
} }
// Preliminary calibration...future a function of bandwidth and BusyDet. // Preliminary calibration...future a function of bandwidth and BusyDet.

View File

@ -29,7 +29,7 @@ extern "C" void get_exclude_list(char * line, TStringList * list);
extern "C" void get_exclude_frm(char * line, TStringList * list); extern "C" void get_exclude_frm(char * line, TStringList * list);
extern "C" int SoundMode; extern "C" int SoundMode;
extern "C" int onlyMixSnoop; extern "C" bool onlyMixSnoop;
//extern "C" int RX_SR; //extern "C" int RX_SR;
//extern "C" int TX_SR; //extern "C" int TX_SR;
@ -59,6 +59,7 @@ extern int CWIDRight;
extern int CWIDType; extern int CWIDType;
extern bool afterTraffic; extern bool afterTraffic;
extern bool darkTheme; extern bool darkTheme;
extern "C" bool useKISSControls;
extern "C" int RSID_SABM[4]; extern "C" int RSID_SABM[4];
extern "C" int RSID_UI[4]; extern "C" int RSID_UI[4];
@ -66,8 +67,10 @@ extern "C" int RSID_SetModem[4];
extern "C" int nonGUIMode; extern "C" int nonGUIMode;
extern char SixPackDevice[256];
extern int SixPackPort;
extern int SixPackEnable;
extern int MgmtPort;
extern QFont Font; extern QFont Font;
@ -216,6 +219,7 @@ void getSettings()
soundChannel[3] = settings->value("Modem/soundChannel4", 0).toInt(); soundChannel[3] = settings->value("Modem/soundChannel4", 0).toInt();
SCO = settings->value("Init/SCO", 0).toInt(); SCO = settings->value("Init/SCO", 0).toInt();
useKISSControls = settings->value("Init/useKISSControls", 0).toBool();
dcd_threshold = settings->value("Modem/DCDThreshold", 40).toInt(); dcd_threshold = settings->value("Modem/DCDThreshold", 40).toInt();
rxOffset = settings->value("Modem/rxOffset", 0).toInt(); rxOffset = settings->value("Modem/rxOffset", 0).toInt();
@ -224,6 +228,11 @@ void getSettings()
AGWPort = settings->value("AGWHost/Port", 8000).toInt(); AGWPort = settings->value("AGWHost/Port", 8000).toInt();
KISSServ = settings->value("KISS/Server", FALSE).toBool(); KISSServ = settings->value("KISS/Server", FALSE).toBool();
KISSPort = settings->value("KISS/Port", 8105).toInt(); KISSPort = settings->value("KISS/Port", 8105).toInt();
MgmtPort = settings->value("MGMT/Port", 0).toInt();
SixPackEnable = settings->value("SixPack/Enable", FALSE).toBool();
SixPackPort = settings->value("SixPack/Port", 0).toInt();
strcpy(SixPackDevice, settings->value("SixPack/Device", "").toString().toUtf8());
// RX_Samplerate = RX_SR + RX_SR * 0.000001*RX_PPM; // RX_Samplerate = RX_SR + RX_SR * 0.000001*RX_PPM;
// TX_Samplerate = TX_SR + TX_SR * 0.000001*TX_PPM; // TX_Samplerate = TX_SR + TX_SR * 0.000001*TX_PPM;
@ -402,6 +411,7 @@ void saveSettings()
settings->setValue("Init/SndRXDeviceName", CaptureDevice); settings->setValue("Init/SndRXDeviceName", CaptureDevice);
settings->setValue("Init/SndTXDeviceName", PlaybackDevice); settings->setValue("Init/SndTXDeviceName", PlaybackDevice);
settings->setValue("Init/useKISSControls", useKISSControls);
settings->setValue("Init/SCO", SCO); settings->setValue("Init/SCO", SCO);
settings->setValue("Init/DualPTT", DualPTT); settings->setValue("Init/DualPTT", DualPTT);
settings->setValue("Init/TXRotate", TX_rotate); settings->setValue("Init/TXRotate", TX_rotate);
@ -460,6 +470,12 @@ void saveSettings()
settings->setValue("AGWHost/Port", AGWPort); settings->setValue("AGWHost/Port", AGWPort);
settings->setValue("KISS/Server", KISSServ); settings->setValue("KISS/Server", KISSServ);
settings->setValue("KISS/Port", KISSPort); settings->setValue("KISS/Port", KISSPort);
settings->setValue("MGMT/Port", MgmtPort);
settings->setValue("SixPack/Enable", SixPackEnable);
settings->setValue("SixPack/Port", SixPackPort);
settings->setValue("SixPack/Device", SixPackDevice);
settings->setValue("Modem/PreEmphasisAll1", emph_all[0]); settings->setValue("Modem/PreEmphasisAll1", emph_all[0]);
settings->setValue("Modem/PreEmphasisAll2", emph_all[1]); settings->setValue("Modem/PreEmphasisAll2", emph_all[1]);

View File

@ -1,481 +1,481 @@
/*extern "C" /*extern "C"
Copyright (C) 2019-2020 Andrei Kopanchuk UZ7HO Copyright (C) 2019-2020 Andrei Kopanchuk UZ7HO
This file is part of QtSoundModem This file is part of QtSoundModem
QtSoundModem is free software: you can redistribute it and/or modify QtSoundModem is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or
(at your option) any later version. (at your option) any later version.
QtSoundModem is distributed in the hope that it will be useful, QtSoundModem is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details. GNU General Public License for more details.
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with QtSoundModem. If not, see http://www.gnu.org/licenses along with QtSoundModem. If not, see http://www.gnu.org/licenses
*/ */
// UZ7HO Soundmodem Port by John Wiseman G8BPQ // UZ7HO Soundmodem Port by John Wiseman G8BPQ
#include <QSettings> #include <QSettings>
#include <QDialog> #include <QDialog>
#include "UZ7HOStuff.h" #include "UZ7HOStuff.h"
extern "C" void get_exclude_list(char * line, TStringList * list); extern "C" void get_exclude_list(char * line, TStringList * list);
extern "C" void get_exclude_frm(char * line, TStringList * list); extern "C" void get_exclude_frm(char * line, TStringList * list);
extern "C" int SoundMode; extern "C" int SoundMode;
extern "C" int RX_SR; extern "C" int RX_SR;
extern "C" int TX_SR; extern "C" int TX_SR;
extern "C" int multiCore; extern "C" int multiCore;
extern "C" char * Wisdom; extern "C" char * Wisdom;
extern int WaterfallMin; extern int WaterfallMin;
extern int WaterfallMax; extern int WaterfallMax;
extern "C" word MEMRecovery[5]; extern "C" word MEMRecovery[5];
extern int MintoTray; extern int MintoTray;
extern "C" int UDPClientPort; extern "C" int UDPClientPort;
extern "C" int UDPServerPort; extern "C" int UDPServerPort;
extern "C" int TXPort; extern "C" int TXPort;
extern char UDPHost[64]; extern char UDPHost[64];
extern QDialog * constellationDialog; extern QDialog * constellationDialog;
extern QRect PSKRect; extern QRect PSKRect;
extern char CWIDCall[128]; extern char CWIDCall[128];
extern "C" char CWIDMark[32]; extern "C" char CWIDMark[32];
extern int CWIDInterval; extern int CWIDInterval;
extern int CWIDLeft; extern int CWIDLeft;
extern int CWIDRight; extern int CWIDRight;
extern int CWIDType; extern int CWIDType;
extern bool afterTraffic; extern bool afterTraffic;
extern bool darkTheme; extern bool darkTheme;
extern "C" int RSID_SABM[4]; extern "C" int RSID_SABM[4];
extern "C" int RSID_UI[4]; extern "C" int RSID_UI[4];
extern "C" int RSID_SetModem[4]; extern "C" int RSID_SetModem[4];
extern QFont Font; extern QFont Font;
QSettings* settings = new QSettings("QtSoundModem.ini", QSettings::IniFormat); QSettings* settings = new QSettings("QtSoundModem.ini", QSettings::IniFormat);
// This makes geting settings for more channels easier // This makes geting settings for more channels easier
char Prefix[16] = "AX25_A"; char Prefix[16] = "AX25_A";
void GetPortSettings(int Chan); void GetPortSettings(int Chan);
QVariant getAX25Param(const char * key, QVariant Default) QVariant getAX25Param(const char * key, QVariant Default)
{ {
char fullKey[64]; char fullKey[64];
QVariant Q; QVariant Q;
QByteArray x; QByteArray x;
sprintf(fullKey, "%s/%s", Prefix, key); sprintf(fullKey, "%s/%s", Prefix, key);
Q = settings->value(fullKey, Default); Q = settings->value(fullKey, Default);
x = Q.toString().toUtf8(); x = Q.toString().toUtf8();
return Q; return Q;
} }
void getAX25Params(int chan) void getAX25Params(int chan)
{ {
Prefix[5] = chan + 'A'; Prefix[5] = chan + 'A';
GetPortSettings(chan); GetPortSettings(chan);
} }
void GetPortSettings(int Chan) void GetPortSettings(int Chan)
{ {
tx_hitoneraisedb[Chan] = getAX25Param("HiToneRaise", 0).toInt(); tx_hitoneraisedb[Chan] = getAX25Param("HiToneRaise", 0).toInt();
maxframe[Chan] = getAX25Param("Maxframe", 3).toInt(); maxframe[Chan] = getAX25Param("Maxframe", 3).toInt();
fracks[Chan] = getAX25Param("Retries", 15).toInt(); fracks[Chan] = getAX25Param("Retries", 15).toInt();
frack_time[Chan] = getAX25Param("FrackTime", 5).toInt(); frack_time[Chan] = getAX25Param("FrackTime", 5).toInt();
idletime[Chan] = getAX25Param("IdleTime", 180).toInt(); idletime[Chan] = getAX25Param("IdleTime", 180).toInt();
slottime[Chan] = getAX25Param("SlotTime", 100).toInt(); slottime[Chan] = getAX25Param("SlotTime", 100).toInt();
persist[Chan] = getAX25Param("Persist", 128).toInt(); persist[Chan] = getAX25Param("Persist", 128).toInt();
resptime[Chan] = getAX25Param("RespTime", 1500).toInt(); resptime[Chan] = getAX25Param("RespTime", 1500).toInt();
TXFrmMode[Chan] = getAX25Param("TXFrmMode", 1).toInt(); TXFrmMode[Chan] = getAX25Param("TXFrmMode", 1).toInt();
max_frame_collector[Chan] = getAX25Param("FrameCollector", 6).toInt(); max_frame_collector[Chan] = getAX25Param("FrameCollector", 6).toInt();
KISS_opt[Chan] = getAX25Param("KISSOptimization", false).toInt();; KISS_opt[Chan] = getAX25Param("KISSOptimization", false).toInt();;
dyn_frack[Chan] = getAX25Param("DynamicFrack", false).toInt();; dyn_frack[Chan] = getAX25Param("DynamicFrack", false).toInt();;
recovery[Chan] = getAX25Param("BitRecovery", 0).toInt(); recovery[Chan] = getAX25Param("BitRecovery", 0).toInt();
NonAX25[Chan] = getAX25Param("NonAX25Frm", false).toInt();; NonAX25[Chan] = getAX25Param("NonAX25Frm", false).toInt();;
MEMRecovery[Chan]= getAX25Param("MEMRecovery", 200).toInt(); MEMRecovery[Chan]= getAX25Param("MEMRecovery", 200).toInt();
IPOLL[Chan] = getAX25Param("IPOLL", 80).toInt(); IPOLL[Chan] = getAX25Param("IPOLL", 80).toInt();
strcpy(MyDigiCall[Chan], getAX25Param("MyDigiCall", "").toString().toUtf8()); strcpy(MyDigiCall[Chan], getAX25Param("MyDigiCall", "").toString().toUtf8());
strcpy(exclude_callsigns[Chan], getAX25Param("ExcludeCallsigns", "").toString().toUtf8()); strcpy(exclude_callsigns[Chan], getAX25Param("ExcludeCallsigns", "").toString().toUtf8());
fx25_mode[Chan] = getAX25Param("FX25", FX25_MODE_RX).toInt(); fx25_mode[Chan] = getAX25Param("FX25", FX25_MODE_RX).toInt();
il2p_mode[Chan] = getAX25Param("IL2P", IL2P_MODE_NONE).toInt(); il2p_mode[Chan] = getAX25Param("IL2P", IL2P_MODE_NONE).toInt();
il2p_crc[Chan] = getAX25Param("IL2PCRC", 0).toInt(); il2p_crc[Chan] = getAX25Param("IL2PCRC", 0).toInt();
RSID_UI[Chan] = getAX25Param("RSID_UI", 0).toInt(); RSID_UI[Chan] = getAX25Param("RSID_UI", 0).toInt();
RSID_SABM[Chan] = getAX25Param("RSID_SABM", 0).toInt(); RSID_SABM[Chan] = getAX25Param("RSID_SABM", 0).toInt();
RSID_SetModem[Chan] = getAX25Param("RSID_SetModem", 0).toInt(); RSID_SetModem[Chan] = getAX25Param("RSID_SetModem", 0).toInt();
} }
void getSettings() void getSettings()
{ {
int snd_ch; int snd_ch;
QSettings* settings = new QSettings("QtSoundModem.ini", QSettings::IniFormat); QSettings* settings = new QSettings("QtSoundModem.ini", QSettings::IniFormat);
settings->sync(); settings->sync();
PSKRect = settings->value("PSKWindow").toRect(); PSKRect = settings->value("PSKWindow").toRect();
SoundMode = settings->value("Init/SoundMode", 0).toInt(); SoundMode = settings->value("Init/SoundMode", 0).toInt();
UDPClientPort = settings->value("Init/UDPClientPort", 8888).toInt(); UDPClientPort = settings->value("Init/UDPClientPort", 8888).toInt();
UDPServerPort = settings->value("Init/UDPServerPort", 8884).toInt(); UDPServerPort = settings->value("Init/UDPServerPort", 8884).toInt();
TXPort = settings->value("Init/TXPort", UDPServerPort).toInt(); TXPort = settings->value("Init/TXPort", UDPServerPort).toInt();
strcpy(UDPHost, settings->value("Init/UDPHost", "192.168.1.255").toString().toUtf8()); strcpy(UDPHost, settings->value("Init/UDPHost", "192.168.1.255").toString().toUtf8());
UDPServ = settings->value("Init/UDPServer", FALSE).toBool(); UDPServ = settings->value("Init/UDPServer", FALSE).toBool();
RX_SR = settings->value("Init/RXSampleRate", 12000).toInt(); RX_SR = settings->value("Init/RXSampleRate", 12000).toInt();
TX_SR = settings->value("Init/TXSampleRate", 12000).toInt(); TX_SR = settings->value("Init/TXSampleRate", 12000).toInt();
strcpy(CaptureDevice, settings->value("Init/SndRXDeviceName", "hw:1,0").toString().toUtf8()); strcpy(CaptureDevice, settings->value("Init/SndRXDeviceName", "hw:1,0").toString().toUtf8());
strcpy(PlaybackDevice, settings->value("Init/SndTXDeviceName", "hw:1,0").toString().toUtf8()); strcpy(PlaybackDevice, settings->value("Init/SndTXDeviceName", "hw:1,0").toString().toUtf8());
raduga = settings->value("Init/DispMode", DISP_RGB).toInt(); raduga = settings->value("Init/DispMode", DISP_RGB).toInt();
strcpy(PTTPort, settings->value("Init/PTT", "").toString().toUtf8()); strcpy(PTTPort, settings->value("Init/PTT", "").toString().toUtf8());
PTTMode = settings->value("Init/PTTMode", 19200).toInt(); PTTMode = settings->value("Init/PTTMode", 19200).toInt();
PTTBAUD = settings->value("Init/PTTBAUD", 19200).toInt(); PTTBAUD = settings->value("Init/PTTBAUD", 19200).toInt();
strcpy(PTTOnString, settings->value("Init/PTTOnString", "").toString().toUtf8()); strcpy(PTTOnString, settings->value("Init/PTTOnString", "").toString().toUtf8());
strcpy(PTTOffString, settings->value("Init/PTTOffString", "").toString().toUtf8()); strcpy(PTTOffString, settings->value("Init/PTTOffString", "").toString().toUtf8());
pttGPIOPin = settings->value("Init/pttGPIOPin", 17).toInt(); pttGPIOPin = settings->value("Init/pttGPIOPin", 17).toInt();
pttGPIOPinR = settings->value("Init/pttGPIOPinR", 17).toInt(); pttGPIOPinR = settings->value("Init/pttGPIOPinR", 17).toInt();
#ifdef WIN32 #ifdef WIN32
strcpy(CM108Addr, settings->value("Init/CM108Addr", "0xD8C:0x08").toString().toUtf8()); strcpy(CM108Addr, settings->value("Init/CM108Addr", "0xD8C:0x08").toString().toUtf8());
#else #else
strcpy(CM108Addr, settings->value("Init/CM108Addr", "/dev/hidraw0").toString().toUtf8()); strcpy(CM108Addr, settings->value("Init/CM108Addr", "/dev/hidraw0").toString().toUtf8());
#endif #endif
HamLibPort = settings->value("Init/HamLibPort", 4532).toInt(); HamLibPort = settings->value("Init/HamLibPort", 4532).toInt();
strcpy(HamLibHost, settings->value("Init/HamLibHost", "127.0.0.1").toString().toUtf8()); strcpy(HamLibHost, settings->value("Init/HamLibHost", "127.0.0.1").toString().toUtf8());
DualPTT = settings->value("Init/DualPTT", 1).toInt(); DualPTT = settings->value("Init/DualPTT", 1).toInt();
TX_rotate = settings->value("Init/TXRotate", 0).toInt(); TX_rotate = settings->value("Init/TXRotate", 0).toInt();
multiCore = settings->value("Init/multiCore", 0).toInt(); multiCore = settings->value("Init/multiCore", 0).toInt();
MintoTray = settings->value("Init/MinimizetoTray", 1).toInt(); MintoTray = settings->value("Init/MinimizetoTray", 1).toInt();
Wisdom = strdup(settings->value("Init/Wisdom", "").toString().toUtf8()); Wisdom = strdup(settings->value("Init/Wisdom", "").toString().toUtf8());
WaterfallMin = settings->value("Init/WaterfallMin", 0).toInt(); WaterfallMin = settings->value("Init/WaterfallMin", 0).toInt();
WaterfallMax = settings->value("Init/WaterfallMax", 3300).toInt(); WaterfallMax = settings->value("Init/WaterfallMax", 3300).toInt();
rx_freq[0] = settings->value("Modem/RXFreq1", 1700).toInt(); rx_freq[0] = settings->value("Modem/RXFreq1", 1700).toInt();
rx_freq[1] = settings->value("Modem/RXFreq2", 1700).toInt(); rx_freq[1] = settings->value("Modem/RXFreq2", 1700).toInt();
rx_freq[2] = settings->value("Modem/RXFreq3", 1700).toInt(); rx_freq[2] = settings->value("Modem/RXFreq3", 1700).toInt();
rx_freq[3] = settings->value("Modem/RXFreq4", 1700).toInt(); rx_freq[3] = settings->value("Modem/RXFreq4", 1700).toInt();
rcvr_offset[0] = settings->value("Modem/RcvrShift1", 30).toInt(); rcvr_offset[0] = settings->value("Modem/RcvrShift1", 30).toInt();
rcvr_offset[1] = settings->value("Modem/RcvrShift2", 30).toInt(); rcvr_offset[1] = settings->value("Modem/RcvrShift2", 30).toInt();
rcvr_offset[2] = settings->value("Modem/RcvrShift3", 30).toInt(); rcvr_offset[2] = settings->value("Modem/RcvrShift3", 30).toInt();
rcvr_offset[3] = settings->value("Modem/RcvrShift4", 30).toInt(); rcvr_offset[3] = settings->value("Modem/RcvrShift4", 30).toInt();
speed[0] = settings->value("Modem/ModemType1", SPEED_1200).toInt(); speed[0] = settings->value("Modem/ModemType1", SPEED_1200).toInt();
speed[1] = settings->value("Modem/ModemType2", SPEED_1200).toInt(); speed[1] = settings->value("Modem/ModemType2", SPEED_1200).toInt();
speed[2] = settings->value("Modem/ModemType3", SPEED_1200).toInt(); speed[2] = settings->value("Modem/ModemType3", SPEED_1200).toInt();
speed[3] = settings->value("Modem/ModemType4", SPEED_1200).toInt(); speed[3] = settings->value("Modem/ModemType4", SPEED_1200).toInt();
RCVR[0] = settings->value("Modem/NRRcvrPairs1", 0).toInt();; RCVR[0] = settings->value("Modem/NRRcvrPairs1", 0).toInt();;
RCVR[1] = settings->value("Modem/NRRcvrPairs2", 0).toInt();; RCVR[1] = settings->value("Modem/NRRcvrPairs2", 0).toInt();;
RCVR[2] = settings->value("Modem/NRRcvrPairs3", 0).toInt();; RCVR[2] = settings->value("Modem/NRRcvrPairs3", 0).toInt();;
RCVR[3] = settings->value("Modem/NRRcvrPairs4", 0).toInt();; RCVR[3] = settings->value("Modem/NRRcvrPairs4", 0).toInt();;
soundChannel[0] = settings->value("Modem/soundChannel1", 1).toInt(); soundChannel[0] = settings->value("Modem/soundChannel1", 1).toInt();
soundChannel[1] = settings->value("Modem/soundChannel2", 0).toInt(); soundChannel[1] = settings->value("Modem/soundChannel2", 0).toInt();
soundChannel[2] = settings->value("Modem/soundChannel3", 0).toInt(); soundChannel[2] = settings->value("Modem/soundChannel3", 0).toInt();
soundChannel[3] = settings->value("Modem/soundChannel4", 0).toInt(); soundChannel[3] = settings->value("Modem/soundChannel4", 0).toInt();
SCO = settings->value("Init/SCO", 0).toInt(); SCO = settings->value("Init/SCO", 0).toInt();
dcd_threshold = settings->value("Modem/DCDThreshold", 40).toInt(); dcd_threshold = settings->value("Modem/DCDThreshold", 40).toInt();
rxOffset = settings->value("Modem/rxOffset", 0).toInt(); rxOffset = settings->value("Modem/rxOffset", 0).toInt();
AGWServ = settings->value("AGWHost/Server", TRUE).toBool(); AGWServ = settings->value("AGWHost/Server", TRUE).toBool();
AGWPort = settings->value("AGWHost/Port", 8000).toInt(); AGWPort = settings->value("AGWHost/Port", 8000).toInt();
KISSServ = settings->value("KISS/Server", FALSE).toBool(); KISSServ = settings->value("KISS/Server", FALSE).toBool();
KISSPort = settings->value("KISS/Port", 8105).toInt(); KISSPort = settings->value("KISS/Port", 8105).toInt();
RX_Samplerate = RX_SR + RX_SR * 0.000001*RX_PPM; RX_Samplerate = RX_SR + RX_SR * 0.000001*RX_PPM;
TX_Samplerate = TX_SR + TX_SR * 0.000001*TX_PPM; TX_Samplerate = TX_SR + TX_SR * 0.000001*TX_PPM;
emph_all[0] = settings->value("Modem/PreEmphasisAll1", FALSE).toBool(); emph_all[0] = settings->value("Modem/PreEmphasisAll1", FALSE).toBool();
emph_all[1] = settings->value("Modem/PreEmphasisAll2", FALSE).toBool(); emph_all[1] = settings->value("Modem/PreEmphasisAll2", FALSE).toBool();
emph_all[2] = settings->value("Modem/PreEmphasisAll3", FALSE).toBool(); emph_all[2] = settings->value("Modem/PreEmphasisAll3", FALSE).toBool();
emph_all[3] = settings->value("Modem/PreEmphasisAll4", FALSE).toBool(); emph_all[3] = settings->value("Modem/PreEmphasisAll4", FALSE).toBool();
emph_db[0] = settings->value("Modem/PreEmphasisDB1", 0).toInt(); emph_db[0] = settings->value("Modem/PreEmphasisDB1", 0).toInt();
emph_db[1] = settings->value("Modem/PreEmphasisDB2", 0).toInt(); emph_db[1] = settings->value("Modem/PreEmphasisDB2", 0).toInt();
emph_db[2] = settings->value("Modem/PreEmphasisDB3", 0).toInt(); emph_db[2] = settings->value("Modem/PreEmphasisDB3", 0).toInt();
emph_db[3] = settings->value("Modem/PreEmphasisDB4", 0).toInt(); emph_db[3] = settings->value("Modem/PreEmphasisDB4", 0).toInt();
Firstwaterfall = settings->value("Window/Waterfall1", TRUE).toInt(); Firstwaterfall = settings->value("Window/Waterfall1", TRUE).toInt();
Secondwaterfall = settings->value("Window/Waterfall2", TRUE).toInt(); Secondwaterfall = settings->value("Window/Waterfall2", TRUE).toInt();
txdelay[0] = settings->value("Modem/TxDelay1", 250).toInt(); txdelay[0] = settings->value("Modem/TxDelay1", 250).toInt();
txdelay[1] = settings->value("Modem/TxDelay2", 250).toInt(); txdelay[1] = settings->value("Modem/TxDelay2", 250).toInt();
txdelay[2] = settings->value("Modem/TxDelay3", 250).toInt(); txdelay[2] = settings->value("Modem/TxDelay3", 250).toInt();
txdelay[3] = settings->value("Modem/TxDelay4", 250).toInt(); txdelay[3] = settings->value("Modem/TxDelay4", 250).toInt();
txtail[0] = settings->value("Modem/TxTail1", 50).toInt(); txtail[0] = settings->value("Modem/TxTail1", 50).toInt();
txtail[1] = settings->value("Modem/TxTail2", 50).toInt(); txtail[1] = settings->value("Modem/TxTail2", 50).toInt();
txtail[2] = settings->value("Modem/TxTail3", 50).toInt(); txtail[2] = settings->value("Modem/TxTail3", 50).toInt();
txtail[3] = settings->value("Modem/TxTail4", 50).toInt(); txtail[3] = settings->value("Modem/TxTail4", 50).toInt();
strcpy(CWIDCall, settings->value("Modem/CWIDCall", "").toString().toUtf8().toUpper()); strcpy(CWIDCall, settings->value("Modem/CWIDCall", "").toString().toUtf8().toUpper());
strcpy(CWIDMark, settings->value("Modem/CWIDMark", "").toString().toUtf8().toUpper()); strcpy(CWIDMark, settings->value("Modem/CWIDMark", "").toString().toUtf8().toUpper());
CWIDInterval = settings->value("Modem/CWIDInterval", 0).toInt(); CWIDInterval = settings->value("Modem/CWIDInterval", 0).toInt();
CWIDLeft = settings->value("Modem/CWIDLeft", 0).toInt(); CWIDLeft = settings->value("Modem/CWIDLeft", 0).toInt();
CWIDRight = settings->value("Modem/CWIDRight", 0).toInt(); CWIDRight = settings->value("Modem/CWIDRight", 0).toInt();
CWIDType = settings->value("Modem/CWIDType", 1).toInt(); // on/off CWIDType = settings->value("Modem/CWIDType", 1).toInt(); // on/off
afterTraffic = settings->value("Modem/afterTraffic", false).toBool(); afterTraffic = settings->value("Modem/afterTraffic", false).toBool();
getAX25Params(0); getAX25Params(0);
getAX25Params(1); getAX25Params(1);
getAX25Params(2); getAX25Params(2);
getAX25Params(3); getAX25Params(3);
// Validate and process settings // Validate and process settings
UsingLeft = 0; UsingLeft = 0;
UsingRight = 0; UsingRight = 0;
UsingBothChannels = 0; UsingBothChannels = 0;
for (int i = 0; i < 4; i++) for (int i = 0; i < 4; i++)
{ {
if (soundChannel[i] == LEFT) if (soundChannel[i] == LEFT)
{ {
UsingLeft = 1; UsingLeft = 1;
modemtoSoundLR[i] = 0; modemtoSoundLR[i] = 0;
} }
else if (soundChannel[i] == RIGHT) else if (soundChannel[i] == RIGHT)
{ {
UsingRight = 1; UsingRight = 1;
modemtoSoundLR[i] = 1; modemtoSoundLR[i] = 1;
} }
} }
if (UsingLeft && UsingRight) if (UsingLeft && UsingRight)
UsingBothChannels = 1; UsingBothChannels = 1;
for (snd_ch = 0; snd_ch < 4; snd_ch++) for (snd_ch = 0; snd_ch < 4; snd_ch++)
{ {
tx_hitoneraise[snd_ch] = powf(10.0f, -abs(tx_hitoneraisedb[snd_ch]) / 20.0f); tx_hitoneraise[snd_ch] = powf(10.0f, -abs(tx_hitoneraisedb[snd_ch]) / 20.0f);
if (IPOLL[snd_ch] < 0) if (IPOLL[snd_ch] < 0)
IPOLL[snd_ch] = 0; IPOLL[snd_ch] = 0;
else if (IPOLL[snd_ch] > 65535) else if (IPOLL[snd_ch] > 65535)
IPOLL[snd_ch] = 65535; IPOLL[snd_ch] = 65535;
if (MEMRecovery[snd_ch] < 1) if (MEMRecovery[snd_ch] < 1)
MEMRecovery[snd_ch] = 1; MEMRecovery[snd_ch] = 1;
// if (MEMRecovery[snd_ch]> 65535) // if (MEMRecovery[snd_ch]> 65535)
// MEMRecovery[snd_ch]= 65535; // MEMRecovery[snd_ch]= 65535;
/* /*
if resptime[snd_ch] < 0 then resptime[snd_ch]= 0; if resptime[snd_ch] < 0 then resptime[snd_ch]= 0;
if resptime[snd_ch] > 65535 then resptime[snd_ch]= 65535; if resptime[snd_ch] > 65535 then resptime[snd_ch]= 65535;
if persist[snd_ch] > 255 then persist[snd_ch]= 255; if persist[snd_ch] > 255 then persist[snd_ch]= 255;
if persist[snd_ch] < 32 then persist[snd_ch]= 32; if persist[snd_ch] < 32 then persist[snd_ch]= 32;
if fracks[snd_ch] < 1 then fracks[snd_ch]= 1; if fracks[snd_ch] < 1 then fracks[snd_ch]= 1;
if frack_time[snd_ch] < 1 then frack_time[snd_ch]= 1; if frack_time[snd_ch] < 1 then frack_time[snd_ch]= 1;
if idletime[snd_ch] < frack_time[snd_ch] then idletime[snd_ch]= 180; if idletime[snd_ch] < frack_time[snd_ch] then idletime[snd_ch]= 180;
*/ */
if (emph_db[snd_ch] < 0 || emph_db[snd_ch] > nr_emph) if (emph_db[snd_ch] < 0 || emph_db[snd_ch] > nr_emph)
emph_db[snd_ch] = 0; emph_db[snd_ch] = 0;
if (max_frame_collector[snd_ch] > 6) max_frame_collector[snd_ch] = 6; if (max_frame_collector[snd_ch] > 6) max_frame_collector[snd_ch] = 6;
if (maxframe[snd_ch] == 0 || maxframe[snd_ch] > 7) maxframe[snd_ch] = 3; if (maxframe[snd_ch] == 0 || maxframe[snd_ch] > 7) maxframe[snd_ch] = 3;
if (qpsk_set[snd_ch].mode > 1) qpsk_set[snd_ch].mode = 0; if (qpsk_set[snd_ch].mode > 1) qpsk_set[snd_ch].mode = 0;
} }
darkTheme = settings->value("Init/darkTheme", false).toBool(); darkTheme = settings->value("Init/darkTheme", false).toBool();
delete(settings); delete(settings);
} }
void SavePortSettings(int Chan); void SavePortSettings(int Chan);
void saveAX25Param(const char * key, QVariant Value) void saveAX25Param(const char * key, QVariant Value)
{ {
char fullKey[64]; char fullKey[64];
sprintf(fullKey, "%s/%s", Prefix, key); sprintf(fullKey, "%s/%s", Prefix, key);
settings->setValue(fullKey, Value); settings->setValue(fullKey, Value);
} }
void saveAX25Params(int chan) void saveAX25Params(int chan)
{ {
Prefix[5] = chan + 'A'; Prefix[5] = chan + 'A';
SavePortSettings(chan); SavePortSettings(chan);
} }
void SavePortSettings(int Chan) void SavePortSettings(int Chan)
{ {
saveAX25Param("Retries", fracks[Chan]); saveAX25Param("Retries", fracks[Chan]);
saveAX25Param("HiToneRaise", tx_hitoneraisedb[Chan]); saveAX25Param("HiToneRaise", tx_hitoneraisedb[Chan]);
saveAX25Param("Maxframe",maxframe[Chan]); saveAX25Param("Maxframe",maxframe[Chan]);
saveAX25Param("Retries", fracks[Chan]); saveAX25Param("Retries", fracks[Chan]);
saveAX25Param("FrackTime", frack_time[Chan]); saveAX25Param("FrackTime", frack_time[Chan]);
saveAX25Param("IdleTime", idletime[Chan]); saveAX25Param("IdleTime", idletime[Chan]);
saveAX25Param("SlotTime", slottime[Chan]); saveAX25Param("SlotTime", slottime[Chan]);
saveAX25Param("Persist", persist[Chan]); saveAX25Param("Persist", persist[Chan]);
saveAX25Param("RespTime", resptime[Chan]); saveAX25Param("RespTime", resptime[Chan]);
saveAX25Param("TXFrmMode", TXFrmMode[Chan]); saveAX25Param("TXFrmMode", TXFrmMode[Chan]);
saveAX25Param("FrameCollector", max_frame_collector[Chan]); saveAX25Param("FrameCollector", max_frame_collector[Chan]);
saveAX25Param("ExcludeCallsigns", exclude_callsigns[Chan]); saveAX25Param("ExcludeCallsigns", exclude_callsigns[Chan]);
saveAX25Param("ExcludeAPRSFrmType", exclude_APRS_frm[Chan]); saveAX25Param("ExcludeAPRSFrmType", exclude_APRS_frm[Chan]);
saveAX25Param("KISSOptimization", KISS_opt[Chan]); saveAX25Param("KISSOptimization", KISS_opt[Chan]);
saveAX25Param("DynamicFrack", dyn_frack[Chan]); saveAX25Param("DynamicFrack", dyn_frack[Chan]);
saveAX25Param("BitRecovery", recovery[Chan]); saveAX25Param("BitRecovery", recovery[Chan]);
saveAX25Param("NonAX25Frm", NonAX25[Chan]); saveAX25Param("NonAX25Frm", NonAX25[Chan]);
saveAX25Param("MEMRecovery", MEMRecovery[Chan]); saveAX25Param("MEMRecovery", MEMRecovery[Chan]);
saveAX25Param("IPOLL", IPOLL[Chan]); saveAX25Param("IPOLL", IPOLL[Chan]);
saveAX25Param("MyDigiCall", MyDigiCall[Chan]); saveAX25Param("MyDigiCall", MyDigiCall[Chan]);
saveAX25Param("FX25", fx25_mode[Chan]); saveAX25Param("FX25", fx25_mode[Chan]);
saveAX25Param("IL2P", il2p_mode[Chan]); saveAX25Param("IL2P", il2p_mode[Chan]);
saveAX25Param("IL2PCRC", il2p_crc[Chan]); saveAX25Param("IL2PCRC", il2p_crc[Chan]);
saveAX25Param("RSID_UI", RSID_UI[Chan]); saveAX25Param("RSID_UI", RSID_UI[Chan]);
saveAX25Param("RSID_SABM", RSID_SABM[Chan]); saveAX25Param("RSID_SABM", RSID_SABM[Chan]);
saveAX25Param("RSID_SetModem", RSID_SetModem[Chan]); saveAX25Param("RSID_SetModem", RSID_SetModem[Chan]);
} }
void saveSettings() void saveSettings()
{ {
QSettings * settings = new QSettings("QtSoundModem.ini", QSettings::IniFormat); QSettings * settings = new QSettings("QtSoundModem.ini", QSettings::IniFormat);
settings->setValue("FontFamily", Font.family()); settings->setValue("FontFamily", Font.family());
settings->setValue("PointSize", Font.pointSize()); settings->setValue("PointSize", Font.pointSize());
settings->setValue("Weight", Font.weight()); settings->setValue("Weight", Font.weight());
settings->setValue("PSKWindow", constellationDialog->geometry()); settings->setValue("PSKWindow", constellationDialog->geometry());
settings->setValue("Init/SoundMode", SoundMode); settings->setValue("Init/SoundMode", SoundMode);
settings->setValue("Init/UDPClientPort", UDPClientPort); settings->setValue("Init/UDPClientPort", UDPClientPort);
settings->setValue("Init/UDPServerPort", UDPServerPort); settings->setValue("Init/UDPServerPort", UDPServerPort);
settings->setValue("Init/TXPort", TXPort); settings->setValue("Init/TXPort", TXPort);
settings->setValue("Init/UDPServer", UDPServ); settings->setValue("Init/UDPServer", UDPServ);
settings->setValue("Init/UDPHost", UDPHost); settings->setValue("Init/UDPHost", UDPHost);
settings->setValue("Init/TXSampleRate", TX_SR); settings->setValue("Init/TXSampleRate", TX_SR);
settings->setValue("Init/RXSampleRate", RX_SR); settings->setValue("Init/RXSampleRate", RX_SR);
settings->setValue("Init/SndRXDeviceName", CaptureDevice); settings->setValue("Init/SndRXDeviceName", CaptureDevice);
settings->setValue("Init/SndTXDeviceName", PlaybackDevice); settings->setValue("Init/SndTXDeviceName", PlaybackDevice);
settings->setValue("Init/SCO", SCO); settings->setValue("Init/SCO", SCO);
settings->setValue("Init/DualPTT", DualPTT); settings->setValue("Init/DualPTT", DualPTT);
settings->setValue("Init/TXRotate", TX_rotate); settings->setValue("Init/TXRotate", TX_rotate);
settings->setValue("Init/DispMode", raduga); settings->setValue("Init/DispMode", raduga);
settings->setValue("Init/PTT", PTTPort); settings->setValue("Init/PTT", PTTPort);
settings->setValue("Init/PTTBAUD", PTTBAUD); settings->setValue("Init/PTTBAUD", PTTBAUD);
settings->setValue("Init/PTTMode", PTTMode); settings->setValue("Init/PTTMode", PTTMode);
settings->setValue("Init/PTTOffString", PTTOffString); settings->setValue("Init/PTTOffString", PTTOffString);
settings->setValue("Init/PTTOnString", PTTOnString); settings->setValue("Init/PTTOnString", PTTOnString);
settings->setValue("Init/pttGPIOPin", pttGPIOPin); settings->setValue("Init/pttGPIOPin", pttGPIOPin);
settings->setValue("Init/pttGPIOPinR", pttGPIOPinR); settings->setValue("Init/pttGPIOPinR", pttGPIOPinR);
settings->setValue("Init/CM108Addr", CM108Addr); settings->setValue("Init/CM108Addr", CM108Addr);
settings->setValue("Init/HamLibPort", HamLibPort); settings->setValue("Init/HamLibPort", HamLibPort);
settings->setValue("Init/HamLibHost", HamLibHost); settings->setValue("Init/HamLibHost", HamLibHost);
settings->setValue("Init/MinimizetoTray", MintoTray); settings->setValue("Init/MinimizetoTray", MintoTray);
settings->setValue("Init/multiCore", multiCore); settings->setValue("Init/multiCore", multiCore);
settings->setValue("Init/Wisdom", Wisdom); settings->setValue("Init/Wisdom", Wisdom);
settings->setValue("Init/WaterfallMin", WaterfallMin); settings->setValue("Init/WaterfallMin", WaterfallMin);
settings->setValue("Init/WaterfallMax", WaterfallMax); settings->setValue("Init/WaterfallMax", WaterfallMax);
// Don't save freq on close as it could be offset by multiple decoders // Don't save freq on close as it could be offset by multiple decoders
settings->setValue("Modem/NRRcvrPairs1", RCVR[0]); settings->setValue("Modem/NRRcvrPairs1", RCVR[0]);
settings->setValue("Modem/NRRcvrPairs2", RCVR[1]); settings->setValue("Modem/NRRcvrPairs2", RCVR[1]);
settings->setValue("Modem/NRRcvrPairs3", RCVR[2]); settings->setValue("Modem/NRRcvrPairs3", RCVR[2]);
settings->setValue("Modem/NRRcvrPairs4", RCVR[3]); settings->setValue("Modem/NRRcvrPairs4", RCVR[3]);
settings->setValue("Modem/RcvrShift1", rcvr_offset[0]); settings->setValue("Modem/RcvrShift1", rcvr_offset[0]);
settings->setValue("Modem/RcvrShift2", rcvr_offset[1]); settings->setValue("Modem/RcvrShift2", rcvr_offset[1]);
settings->setValue("Modem/RcvrShift3", rcvr_offset[2]); settings->setValue("Modem/RcvrShift3", rcvr_offset[2]);
settings->setValue("Modem/RcvrShift4", rcvr_offset[3]); settings->setValue("Modem/RcvrShift4", rcvr_offset[3]);
settings->setValue("Modem/ModemType1", speed[0]); settings->setValue("Modem/ModemType1", speed[0]);
settings->setValue("Modem/ModemType2", speed[1]); settings->setValue("Modem/ModemType2", speed[1]);
settings->setValue("Modem/ModemType3", speed[2]); settings->setValue("Modem/ModemType3", speed[2]);
settings->setValue("Modem/ModemType4", speed[3]); settings->setValue("Modem/ModemType4", speed[3]);
settings->setValue("Modem/soundChannel1", soundChannel[0]); settings->setValue("Modem/soundChannel1", soundChannel[0]);
settings->setValue("Modem/soundChannel2", soundChannel[1]); settings->setValue("Modem/soundChannel2", soundChannel[1]);
settings->setValue("Modem/soundChannel3", soundChannel[2]); settings->setValue("Modem/soundChannel3", soundChannel[2]);
settings->setValue("Modem/soundChannel4", soundChannel[3]); settings->setValue("Modem/soundChannel4", soundChannel[3]);
settings->setValue("Modem/DCDThreshold", dcd_threshold); settings->setValue("Modem/DCDThreshold", dcd_threshold);
settings->setValue("Modem/rxOffset", rxOffset); settings->setValue("Modem/rxOffset", rxOffset);
settings->setValue("AGWHost/Server", AGWServ); settings->setValue("AGWHost/Server", AGWServ);
settings->setValue("AGWHost/Port", AGWPort); settings->setValue("AGWHost/Port", AGWPort);
settings->setValue("KISS/Server", KISSServ); settings->setValue("KISS/Server", KISSServ);
settings->setValue("KISS/Port", KISSPort); settings->setValue("KISS/Port", KISSPort);
settings->setValue("Modem/PreEmphasisAll1", emph_all[0]); settings->setValue("Modem/PreEmphasisAll1", emph_all[0]);
settings->setValue("Modem/PreEmphasisAll2", emph_all[1]); settings->setValue("Modem/PreEmphasisAll2", emph_all[1]);
settings->setValue("Modem/PreEmphasisAll3", emph_all[2]); settings->setValue("Modem/PreEmphasisAll3", emph_all[2]);
settings->setValue("Modem/PreEmphasisAll4", emph_all[3]); settings->setValue("Modem/PreEmphasisAll4", emph_all[3]);
settings->setValue("Modem/PreEmphasisDB1", emph_db[0]); settings->setValue("Modem/PreEmphasisDB1", emph_db[0]);
settings->setValue("Modem/PreEmphasisDB2", emph_db[1]); settings->setValue("Modem/PreEmphasisDB2", emph_db[1]);
settings->setValue("Modem/PreEmphasisDB3", emph_db[2]); settings->setValue("Modem/PreEmphasisDB3", emph_db[2]);
settings->setValue("Modem/PreEmphasisDB4", emph_db[3]); settings->setValue("Modem/PreEmphasisDB4", emph_db[3]);
settings->setValue("Window/Waterfall1", Firstwaterfall); settings->setValue("Window/Waterfall1", Firstwaterfall);
settings->setValue("Window/Waterfall2", Secondwaterfall); settings->setValue("Window/Waterfall2", Secondwaterfall);
settings->setValue("Modem/TxDelay1", txdelay[0]); settings->setValue("Modem/TxDelay1", txdelay[0]);
settings->setValue("Modem/TxDelay2", txdelay[1]); settings->setValue("Modem/TxDelay2", txdelay[1]);
settings->setValue("Modem/TxDelay3", txdelay[2]); settings->setValue("Modem/TxDelay3", txdelay[2]);
settings->setValue("Modem/TxDelay4", txdelay[3]); settings->setValue("Modem/TxDelay4", txdelay[3]);
settings->setValue("Modem/TxTail1", txtail[0]); settings->setValue("Modem/TxTail1", txtail[0]);
settings->setValue("Modem/TxTail2", txtail[1]); settings->setValue("Modem/TxTail2", txtail[1]);
settings->setValue("Modem/TxTail3", txtail[2]); settings->setValue("Modem/TxTail3", txtail[2]);
settings->setValue("Modem/TxTail4", txtail[3]); settings->setValue("Modem/TxTail4", txtail[3]);
settings->setValue("Modem/CWIDCall", CWIDCall); settings->setValue("Modem/CWIDCall", CWIDCall);
settings->setValue("Modem/CWIDMark", CWIDMark); settings->setValue("Modem/CWIDMark", CWIDMark);
settings->setValue("Modem/CWIDInterval", CWIDInterval); settings->setValue("Modem/CWIDInterval", CWIDInterval);
settings->setValue("Modem/CWIDLeft", CWIDLeft); settings->setValue("Modem/CWIDLeft", CWIDLeft);
settings->setValue("Modem/CWIDRight", CWIDRight); settings->setValue("Modem/CWIDRight", CWIDRight);
settings->setValue("Modem/CWIDType", CWIDType); settings->setValue("Modem/CWIDType", CWIDType);
settings->setValue("Modem/afterTraffic", afterTraffic); settings->setValue("Modem/afterTraffic", afterTraffic);
settings->setValue("Init/darkTheme", darkTheme); settings->setValue("Init/darkTheme", darkTheme);
saveAX25Params(0); saveAX25Params(0);
saveAX25Params(1); saveAX25Params(1);
saveAX25Params(2); saveAX25Params(2);
saveAX25Params(3); saveAX25Params(3);
settings->sync(); settings->sync();
delete(settings); delete(settings);
} }

View File

@ -1025,6 +1025,34 @@ void sendCWID(char * strID, BOOL CWOnOff, int Chan)
initFilter(200, Filter, Chan); initFilter(200, Filter, Chan);
// if sending 1500 cal tone send mark tone for 10 secs
if (strcmp(strID, "1500TONE") == 0)
{
float m_amplitude = 30000.0f;
float m_frequency = 1500.0f;
float m_phase = 0.0;
float m_time = 0.0;
float m_deltaTime = 1.0f / 12000;
float x;
// generate sin wave in mono
for (int sample = 0; sample < 120000; ++sample)
{
x = m_amplitude * sin(2 * M_PI * m_frequency * m_time + m_phase);
ARDOPSampleSink(x);
m_time += m_deltaTime;
}
ARDOPTXPtr[Chan] = 0;
ARDOPTXLen[Chan] = Number;
Number = 0;
return;
}
//Generate leader for VOX 6 dots long //Generate leader for VOX 6 dots long
for (k = 6; k >0; k--) for (k = 6; k >0; k--)

View File

@ -71,6 +71,7 @@ QTextEdit * monWindowCopy;
extern workerThread *t; extern workerThread *t;
extern QtSoundModem * w; extern QtSoundModem * w;
extern QCoreApplication * a; extern QCoreApplication * a;
extern serialThread *serial;
QList<QSerialPortInfo> Ports = QSerialPortInfo::availablePorts(); QList<QSerialPortInfo> Ports = QSerialPortInfo::availablePorts();
@ -95,7 +96,7 @@ extern "C" char CaptureNames[16][256];
extern "C" char PlaybackNames[16][256]; extern "C" char PlaybackNames[16][256];
extern "C" int SoundMode; extern "C" int SoundMode;
extern "C" int onlyMixSnoop; extern "C" bool onlyMixSnoop;
extern "C" int multiCore; extern "C" int multiCore;
@ -118,6 +119,8 @@ extern "C" int SendSize; // 100 mS for now
extern "C" int txLatency; extern "C" int txLatency;
extern "C" int BusyDet;
extern "C" extern "C"
{ {
int InitSound(BOOL Report); int InitSound(BOOL Report);
@ -169,6 +172,8 @@ int Configuring = 0;
bool lockWaterfall = false; bool lockWaterfall = false;
bool inWaterfall = false; bool inWaterfall = false;
int MgmtPort = 0;
extern "C" int NeedWaterfallHeaders; extern "C" int NeedWaterfallHeaders;
extern "C" float BinSize; extern "C" float BinSize;
@ -192,6 +197,7 @@ QRgb rxText = qRgb(0, 0, 192);
bool darkTheme = true; bool darkTheme = true;
bool minimizeonStart = true; bool minimizeonStart = true;
extern "C" bool useKISSControls;
// Indexed colour list from ARDOPC // Indexed colour list from ARDOPC
@ -241,6 +247,21 @@ int MintoTray = 1;
int RSID_WF = 0; // Set to use RSID FFT for Waterfall. int RSID_WF = 0; // Set to use RSID FFT for Waterfall.
char SixPackDevice[256] = "";
int SixPackPort = 0;
int SixPackEnable = 0;
// Stats
uint64_t PTTonTime[4] = { 0 };
uint64_t PTTActivemS[4] = { 0 }; // For Stats
uint64_t BusyonTime[4] = { 0 };
uint64_t BusyActivemS[4] = { 0 };
int AvPTT[4] = { 0 };
int AvBusy[4] = { 0 };
extern "C" void WriteDebugLog(char * Mess) extern "C" void WriteDebugLog(char * Mess)
{ {
qDebug() << Mess; qDebug() << Mess;
@ -249,6 +270,24 @@ extern "C" void WriteDebugLog(char * Mess)
void QtSoundModem::doupdateDCD(int Chan, int State) void QtSoundModem::doupdateDCD(int Chan, int State)
{ {
DCDLabel[Chan]->setVisible(State); DCDLabel[Chan]->setVisible(State);
// This also tries to get a percentage on time over a minute
uint64_t Time = QDateTime::currentMSecsSinceEpoch();
if (State)
{
BusyonTime[Chan] = Time;
return;
}
if (BusyonTime[Chan])
{
BusyActivemS[Chan] += Time - BusyonTime[Chan];
BusyonTime[Chan] = 0;
}
} }
extern "C" char * frame_monitor(string * frame, char * code, bool tx_stat); extern "C" char * frame_monitor(string * frame, char * code, bool tx_stat);
@ -529,6 +568,8 @@ QtSoundModem::QtSoundModem(QWidget *parent) : QMainWindow(parent)
getSettings(); getSettings();
serial = new serialThread;
QSettings mysettings("QtSoundModem.ini", QSettings::IniFormat); QSettings mysettings("QtSoundModem.ini", QSettings::IniFormat);
family = mysettings.value("FontFamily", "Courier New").toString(); family = mysettings.value("FontFamily", "Courier New").toString();
@ -790,6 +831,10 @@ QtSoundModem::QtSoundModem(QWidget *parent) : QMainWindow(parent)
connect(timer, SIGNAL(timeout()), this, SLOT(MyTimerSlot())); connect(timer, SIGNAL(timeout()), this, SLOT(MyTimerSlot()));
timer->start(100); timer->start(100);
QTimer *statstimer = new QTimer(this);
connect(statstimer, SIGNAL(timeout()), this, SLOT(StatsTimer()));
statstimer->start(60000); // One Minute
wftimer = new QTimer(this); wftimer = new QTimer(this);
connect(wftimer, SIGNAL(timeout()), this, SLOT(doRestartWF())); connect(wftimer, SIGNAL(timeout()), this, SLOT(doRestartWF()));
// wftimer->start(1000 * 300); // wftimer->start(1000 * 300);
@ -812,6 +857,9 @@ QtSoundModem::QtSoundModem(QWidget *parent) : QMainWindow(parent)
QTimer::singleShot(200, this, &QtSoundModem::updateFont); QTimer::singleShot(200, this, &QtSoundModem::updateFont);
connect(serial, &serialThread::request, this, &QtSoundModem::showRequest);
} }
void QtSoundModem::updateFont() void QtSoundModem::updateFont()
@ -875,7 +923,113 @@ void extSetOffset(int chan)
return; return;
} }
extern TMgmtMode ** MgmtConnections;
extern int MgmtConCount;
extern QList<QTcpSocket*> _MgmtSockets;
extern "C" void doAGW2MinTimer();
#define FEND 0xc0
#define QTSMKISSCMD 7
int AGW2MinTimer = 0;
void QtSoundModem::StatsTimer()
{
// Calculate % Busy over last minute
for (int n = 0; n < 4; n++)
{
if (soundChannel[n] == 0) // Channel not used
continue;
AvPTT[n] = PTTActivemS[n] / 600; // ms but want %
PTTActivemS[n] = 0;
AvBusy[n] = BusyActivemS[n] / 600;
BusyActivemS[n] = 0;
// send to any connected Mgmt streams
char Msg[64];
uint64_t ret;
if (!useKISSControls)
{
for (QTcpSocket* socket : _MgmtSockets)
{
// Find Session
TMgmtMode * MGMT = NULL;
for (int i = 0; i < MgmtConCount; i++)
{
if (MgmtConnections[i]->Socket == socket)
{
MGMT = MgmtConnections[i];
break;
}
}
if (MGMT == NULL)
continue;
if (MGMT->BPQPort[n])
{
sprintf(Msg, "STATS %d %d %d\r", MGMT->BPQPort[n], AvPTT[n], AvBusy[n]);
ret = socket->write(Msg);
}
}
}
else // useKISSControls set
{
UCHAR * Control = (UCHAR *)malloc(32);
int len = sprintf((char *)Control, "%c%cSTATS %d %d%c", FEND, (n) << 4 | QTSMKISSCMD, AvPTT[n], AvBusy[n], FEND);
KISSSendtoServer(NULL, Control, len);
}
}
AGW2MinTimer++;
if (AGW2MinTimer > 1)
{
AGW2MinTimer = 0;
doAGW2MinTimer();
}
}
// PTT Stats
extern "C" void UpdatePTTStats(int Chan, int State)
{
uint64_t Time = QDateTime::currentMSecsSinceEpoch();
if (State)
{
PTTonTime[Chan] = Time;
// Cancel Busy timer (stats include ptt on time in port active
if (BusyonTime[Chan])
{
BusyActivemS[Chan] += (Time - BusyonTime[Chan]);
BusyonTime[Chan] = 0;
}
}
else
{
if (PTTonTime[Chan])
{
PTTActivemS[Chan] += (Time - PTTonTime[Chan]);
PTTonTime[Chan] = 0;
}
}
}
void QtSoundModem::MyTimerSlot() void QtSoundModem::MyTimerSlot()
{ {
// 100 mS Timer Event // 100 mS Timer Event
@ -1083,6 +1237,8 @@ void QtSoundModem::clickedSlotI(int i)
if (strcmp(Name, "DCDSlider") == 0) if (strcmp(Name, "DCDSlider") == 0)
{ {
dcd_threshold = i; dcd_threshold = i;
BusyDet = i / 10; // for ardop busy detect code
saveSettings(); saveSettings();
return; return;
} }
@ -1264,6 +1420,16 @@ void QtSoundModem::clickedSlot()
return; return;
} }
if (strcmp(Name, "Cal1500") == 0)
{
char call[] = "1500TONE";
sendCWID(call, 0, 0);
calib_mode[0] = 4;
return;
}
if (strcmp(Name, "actFont") == 0) if (strcmp(Name, "actFont") == 0)
{ {
bool ok; bool ok;
@ -2009,6 +2175,7 @@ bool myResize::eventFilter(QObject *obj, QEvent *event)
void QtSoundModem::doDevices() void QtSoundModem::doDevices()
{ {
char valChar[10]; char valChar[10];
QStringList items;
Dev = new(Ui_devicesDialog); Dev = new(Ui_devicesDialog);
@ -2025,6 +2192,22 @@ void QtSoundModem::doDevices()
UI.installEventFilter(resize); UI.installEventFilter(resize);
// Set serial names
for (const QSerialPortInfo &info : Ports)
{
items.append(info.portName());
}
items.sort();
Dev->SixPackSerial->addItem("None");
for (const QString &info : items)
{
Dev->SixPackSerial->addItem(info);
}
newSoundMode = SoundMode; newSoundMode = SoundMode;
oldSoundMode = SoundMode; oldSoundMode = SoundMode;
oldSnoopMix = newSnoopMix = onlyMixSnoop; oldSnoopMix = newSnoopMix = onlyMixSnoop;
@ -2100,6 +2283,7 @@ void QtSoundModem::doDevices()
QStandardItem * item = model->item(0, 0); QStandardItem * item = model->item(0, 0);
item->setEnabled(false); item->setEnabled(false);
Dev->useKISSControls->setChecked(useKISSControls);
Dev->singleChannelOutput->setChecked(SCO); Dev->singleChannelOutput->setChecked(SCO);
Dev->colourWaterfall->setChecked(raduga); Dev->colourWaterfall->setChecked(raduga);
@ -2111,6 +2295,26 @@ void QtSoundModem::doDevices()
Dev->AGWPort->setText(valChar); Dev->AGWPort->setText(valChar);
Dev->AGWEnabled->setChecked(AGWServ); Dev->AGWEnabled->setChecked(AGWServ);
Dev->MgmtPort->setText(QString::number(MgmtPort));
// If we are using a user specifed device add it
i = Dev->SixPackSerial->findText(SixPackDevice, Qt::MatchFixedString);
if (i == -1)
{
// Add our device to list
Dev->SixPackSerial->insertItem(0, SixPackDevice);
i = Dev->SixPackSerial->findText(SixPackDevice, Qt::MatchContains);
}
Dev->SixPackSerial->setCurrentIndex(i);
sprintf(valChar, "%d", SixPackPort);
Dev->SixPackTCP->setText(valChar);
Dev->SixPackEnable->setChecked(SixPackEnable);
Dev->PTTOn->setText(PTTOnString); Dev->PTTOn->setText(PTTOnString);
Dev->PTTOff->setText(PTTOffString); Dev->PTTOff->setText(PTTOffString);
@ -2137,8 +2341,6 @@ void QtSoundModem::doDevices()
Dev->VIDPID->setText(CM108Addr); Dev->VIDPID->setText(CM108Addr);
QStringList items;
connect(Dev->CAT, SIGNAL(toggled(bool)), this, SLOT(CATChanged(bool))); connect(Dev->CAT, SIGNAL(toggled(bool)), this, SLOT(CATChanged(bool)));
connect(Dev->DualPTT, SIGNAL(toggled(bool)), this, SLOT(DualPTTChanged(bool))); connect(Dev->DualPTT, SIGNAL(toggled(bool)), this, SLOT(DualPTTChanged(bool)));
connect(Dev->PTTPort, SIGNAL(currentIndexChanged(int)), this, SLOT(PTTPortChanged(int))); connect(Dev->PTTPort, SIGNAL(currentIndexChanged(int)), this, SLOT(PTTPortChanged(int)));
@ -2148,13 +2350,6 @@ void QtSoundModem::doDevices()
else else
Dev->RTSDTR->setChecked(true); Dev->RTSDTR->setChecked(true);
for (const QSerialPortInfo &info : Ports)
{
items.append(info.portName());
}
items.sort();
Dev->PTTPort->addItem("None"); Dev->PTTPort->addItem("None");
Dev->PTTPort->addItem("CM108"); Dev->PTTPort->addItem("CM108");
@ -2342,6 +2537,8 @@ void QtSoundModem::deviceaccept()
if (UsingLeft && UsingRight) if (UsingLeft && UsingRight)
UsingBothChannels = 1; UsingBothChannels = 1;
useKISSControls = Dev->useKISSControls->isChecked();
SCO = Dev->singleChannelOutput->isChecked(); SCO = Dev->singleChannelOutput->isChecked();
raduga = Dev->colourWaterfall->isChecked(); raduga = Dev->colourWaterfall->isChecked();
AGWServ = Dev->AGWEnabled->isChecked(); AGWServ = Dev->AGWEnabled->isChecked();
@ -2353,9 +2550,26 @@ void QtSoundModem::deviceaccept()
Q = Dev->AGWPort->text(); Q = Dev->AGWPort->text();
AGWPort = Q.toInt(); AGWPort = Q.toInt();
Q = Dev->MgmtPort->text();
MgmtPort = Q.toInt();
Q = Dev->SixPackSerial->currentText();
char temp[256];
strcpy(temp, Q.toString().toUtf8());
if (strlen(temp))
strcpy(SixPackDevice, temp);
Q = Dev->SixPackTCP->text();
SixPackPort = Q.toInt();
SixPackEnable = Dev->SixPackEnable->isChecked();
Q = Dev->PTTPort->currentText(); Q = Dev->PTTPort->currentText();
char temp[256];
strcpy(temp, Q.toString().toUtf8()); strcpy(temp, Q.toString().toUtf8());
@ -2588,6 +2802,7 @@ void QtSoundModem::doCalibrate()
connect(Calibrate.High_D, SIGNAL(released()), this, SLOT(clickedSlot())); connect(Calibrate.High_D, SIGNAL(released()), this, SLOT(clickedSlot()));
connect(Calibrate.Both_D, SIGNAL(released()), this, SLOT(clickedSlot())); connect(Calibrate.Both_D, SIGNAL(released()), this, SLOT(clickedSlot()));
connect(Calibrate.Stop_D, SIGNAL(released()), this, SLOT(clickedSlot())); connect(Calibrate.Stop_D, SIGNAL(released()), this, SLOT(clickedSlot()));
connect(Calibrate.Cal1500, SIGNAL(released()), this, SLOT(clickedSlot()));
/* /*
@ -3502,7 +3717,7 @@ extern "C" int openTraceLog()
return 1; return 1;
} }
extern "C" qint64 writeTraceLog(char * Data, char Dirn) extern "C" qint64 writeTraceLog(char * Data)
{ {
return tracefile.write(Data); return tracefile.write(Data);
} }
@ -3534,7 +3749,7 @@ extern "C" void debugTimeStamp(char * Text, char Dirn)
char Msg[2048]; char Msg[2048];
sprintf(Msg, "%s %s\n", String.toUtf8().data(), Text); sprintf(Msg, "%s %s\n", String.toUtf8().data(), Text);
qint64 ret = writeTraceLog(Msg, Dirn); writeTraceLog(Msg);
} }
@ -3599,3 +3814,76 @@ void QtSoundModem::StartWatchdog()
} }
// KISS Serial Port code - mainly for 6Pack but should work with KISS as well
// Serial Read needs to block and signal the main thread whenever a character is received. TX can probably be uncontrolled
void serialThread::startSlave(const QString &portName, int waitTimeout, const QString &response)
{
QMutexLocker locker(&mutex);
this->portName = portName;
this->waitTimeout = waitTimeout;
this->response = response;
if (!isRunning())
start();
}
void serialThread::run()
{
QSerialPort serial;
bool currentPortNameChanged = false;
mutex.lock();
QString currentPortName;
if (currentPortName != portName) {
currentPortName = portName;
currentPortNameChanged = true;
}
int currentWaitTimeout = waitTimeout;
QString currentRespone = response;
mutex.unlock();
if (currentPortName.isEmpty())
{
Debugprintf("Port not set");
return;
}
serial.setPortName(currentPortName);
if (!serial.open(QIODevice::ReadWrite))
{
Debugprintf("Can't open %s, error code %d", portName, serial.error());
return;
}
while (1)
{
if (serial.waitForReadyRead(currentWaitTimeout))
{
// read request
QByteArray requestData = serial.readAll();
while (serial.waitForReadyRead(10))
requestData += serial.readAll();
// Pass data to 6pack handler
emit this->request(requestData);
}
else {
Debugprintf("Serial read request timeout");
}
}
}
void Process6PackData(unsigned char * Bytes, int Len);
void QtSoundModem::showRequest(QByteArray Data)
{
Process6PackData((unsigned char *)Data.data(), Data.length());
}

File diff suppressed because it is too large Load Diff

View File

@ -43,6 +43,7 @@ private slots:
void updateFont(); void updateFont();
void MinimizetoTray(); void MinimizetoTray();
void TrayActivated(QSystemTrayIcon::ActivationReason reason); void TrayActivated(QSystemTrayIcon::ActivationReason reason);
void StatsTimer();
void MyTimerSlot(); void MyTimerSlot();
void returnPressed(); void returnPressed();
void clickedSlotI(int i); void clickedSlotI(int i);
@ -77,6 +78,7 @@ private slots:
void StartWatchdog(); void StartWatchdog();
void StopWatchdog(); void StopWatchdog();
void PTTWatchdogExpired(); void PTTWatchdogExpired();
void showRequest(QByteArray Data);
void clickedSlot(); void clickedSlot();
void startCWIDTimerSlot(); void startCWIDTimerSlot();
void setWaterfallImage(); void setWaterfallImage();
@ -124,3 +126,25 @@ protected:
#define WaterfallTotalPixels WaterfallDisplayPixels + WaterfallHeaderPixels #define WaterfallTotalPixels WaterfallDisplayPixels + WaterfallHeaderPixels
#define WaterfallImageHeight (WaterfallTotalPixels + WaterfallTotalPixels) #define WaterfallImageHeight (WaterfallTotalPixels + WaterfallTotalPixels)
class serialThread : public QThread
{
Q_OBJECT
public:
void run() Q_DECL_OVERRIDE;
void startSlave(const QString &portName, int waitTimeout, const QString &response);
signals:
void request(const QByteArray &s);
void error(const QString &s);
void timeout(const QString &s);
private:
QString portName;
QString response;
int waitTimeout;
QMutex mutex;
bool quit;
};

View File

@ -44,8 +44,8 @@ SOURCES += ./audio.c \
./ofdm.c \ ./ofdm.c \
./pktARDOP.c \ ./pktARDOP.c \
./BusyDetect.c \ ./BusyDetect.c \
./DW9600.c ./DW9600.c \
./6pack.cpp
FORMS += ./calibrateDialog.ui \ FORMS += ./calibrateDialog.ui \

263
QtSoundModem.pro.user Normal file
View File

@ -0,0 +1,263 @@
<?xml version="1.0" encoding="UTF-8"?>
<!DOCTYPE QtCreatorProject>
<!-- Written by QtCreator 11.0.3, 2024-08-15T14:29:24. -->
<qtcreator>
<data>
<variable>EnvironmentId</variable>
<value type="QByteArray">{6e41d268-43e9-43ac-b8fa-a3c083d547a3}</value>
</data>
<data>
<variable>ProjectExplorer.Project.ActiveTarget</variable>
<value type="qlonglong">0</value>
</data>
<data>
<variable>ProjectExplorer.Project.EditorSettings</variable>
<valuemap type="QVariantMap">
<value type="bool" key="EditorConfiguration.AutoIndent">true</value>
<value type="bool" key="EditorConfiguration.AutoSpacesForTabs">false</value>
<value type="bool" key="EditorConfiguration.CamelCaseNavigation">true</value>
<valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.0">
<value type="QString" key="language">Cpp</value>
<valuemap type="QVariantMap" key="value">
<value type="QByteArray" key="CurrentPreferences">CppGlobal</value>
</valuemap>
</valuemap>
<valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.1">
<value type="QString" key="language">QmlJS</value>
<valuemap type="QVariantMap" key="value">
<value type="QByteArray" key="CurrentPreferences">QmlJSGlobal</value>
</valuemap>
</valuemap>
<value type="qlonglong" key="EditorConfiguration.CodeStyle.Count">2</value>
<value type="QByteArray" key="EditorConfiguration.Codec">UTF-8</value>
<value type="bool" key="EditorConfiguration.ConstrainTooltips">false</value>
<value type="int" key="EditorConfiguration.IndentSize">4</value>
<value type="bool" key="EditorConfiguration.KeyboardTooltips">false</value>
<value type="int" key="EditorConfiguration.MarginColumn">80</value>
<value type="bool" key="EditorConfiguration.MouseHiding">true</value>
<value type="bool" key="EditorConfiguration.MouseNavigation">true</value>
<value type="int" key="EditorConfiguration.PaddingMode">1</value>
<value type="bool" key="EditorConfiguration.PreferSingleLineComments">false</value>
<value type="bool" key="EditorConfiguration.ScrollWheelZooming">true</value>
<value type="bool" key="EditorConfiguration.ShowMargin">false</value>
<value type="int" key="EditorConfiguration.SmartBackspaceBehavior">0</value>
<value type="bool" key="EditorConfiguration.SmartSelectionChanging">true</value>
<value type="bool" key="EditorConfiguration.SpacesForTabs">true</value>
<value type="int" key="EditorConfiguration.TabKeyBehavior">0</value>
<value type="int" key="EditorConfiguration.TabSize">8</value>
<value type="bool" key="EditorConfiguration.UseGlobal">true</value>
<value type="bool" key="EditorConfiguration.UseIndenter">false</value>
<value type="int" key="EditorConfiguration.Utf8BomBehavior">1</value>
<value type="bool" key="EditorConfiguration.addFinalNewLine">true</value>
<value type="bool" key="EditorConfiguration.cleanIndentation">true</value>
<value type="bool" key="EditorConfiguration.cleanWhitespace">true</value>
<value type="QString" key="EditorConfiguration.ignoreFileTypes">*.md, *.MD, Makefile</value>
<value type="bool" key="EditorConfiguration.inEntireDocument">false</value>
<value type="bool" key="EditorConfiguration.skipTrailingWhitespace">true</value>
<value type="bool" key="EditorConfiguration.tintMarginArea">true</value>
</valuemap>
</data>
<data>
<variable>ProjectExplorer.Project.PluginSettings</variable>
<valuemap type="QVariantMap">
<valuemap type="QVariantMap" key="AutoTest.ActiveFrameworks">
<value type="bool" key="AutoTest.Framework.Boost">true</value>
<value type="bool" key="AutoTest.Framework.CTest">false</value>
<value type="bool" key="AutoTest.Framework.Catch">true</value>
<value type="bool" key="AutoTest.Framework.GTest">true</value>
<value type="bool" key="AutoTest.Framework.QtQuickTest">true</value>
<value type="bool" key="AutoTest.Framework.QtTest">true</value>
</valuemap>
<valuemap type="QVariantMap" key="AutoTest.CheckStates"/>
<value type="int" key="AutoTest.RunAfterBuild">0</value>
<value type="bool" key="AutoTest.UseGlobal">true</value>
<valuemap type="QVariantMap" key="ClangTools">
<value type="bool" key="ClangTools.AnalyzeOpenFiles">true</value>
<value type="bool" key="ClangTools.BuildBeforeAnalysis">true</value>
<value type="QString" key="ClangTools.DiagnosticConfig">Builtin.DefaultTidyAndClazy</value>
<value type="int" key="ClangTools.ParallelJobs">0</value>
<value type="bool" key="ClangTools.PreferConfigFile">true</value>
<valuelist type="QVariantList" key="ClangTools.SelectedDirs"/>
<valuelist type="QVariantList" key="ClangTools.SelectedFiles"/>
<valuelist type="QVariantList" key="ClangTools.SuppressedDiagnostics"/>
<value type="bool" key="ClangTools.UseGlobalSettings">true</value>
</valuemap>
</valuemap>
</data>
<data>
<variable>ProjectExplorer.Project.Target.0</variable>
<valuemap type="QVariantMap">
<value type="QString" key="DeviceType">Desktop</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop (x86-darwin-generic-mach_o-64bit)</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop (x86-darwin-generic-mach_o-64bit)</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">{a36d9ffa-38ce-4dfc-9820-5a456a9dc53d}</value>
<value type="qlonglong" key="ProjectExplorer.Target.ActiveBuildConfiguration">0</value>
<value type="qlonglong" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value>
<value type="qlonglong" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value>
<valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.0">
<value type="int" key="EnableQmlDebugging">0</value>
<value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/Volumes/Source/QT/build-QtSoundModem-Desktop_x86_darwin_generic_mach_o_64bit-Debug</value>
<value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory.shadowDir">/Volumes/Source/QT/build-QtSoundModem-Desktop_x86_darwin_generic_mach_o_64bit-Debug</value>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
<value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
<valuelist type="QVariantList" key="QtProjectManager.QMakeBuildStep.SelectedAbis"/>
</valuemap>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
</valuemap>
<value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Build</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
</valuemap>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
<value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
</valuemap>
<value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Clean</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
</valuemap>
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
<value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
<valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.CustomParsers"/>
<value type="bool" key="ProjectExplorer.BuildConfiguration.ParseStandardOutput">false</value>
<valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Debug</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
<value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">2</value>
</valuemap>
<valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.1">
<value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/Volumes/Source/QT/build-QtSoundModem-Desktop_x86_darwin_generic_mach_o_64bit-Release</value>
<value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory.shadowDir">/Volumes/Source/QT/build-QtSoundModem-Desktop_x86_darwin_generic_mach_o_64bit-Release</value>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
<value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
<valuelist type="QVariantList" key="QtProjectManager.QMakeBuildStep.SelectedAbis"/>
</valuemap>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
</valuemap>
<value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Build</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
</valuemap>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
<value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
</valuemap>
<value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Clean</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
</valuemap>
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
<value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
<valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.CustomParsers"/>
<value type="bool" key="ProjectExplorer.BuildConfiguration.ParseStandardOutput">false</value>
<valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Release</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
<value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">0</value>
<value type="int" key="QtQuickCompiler">0</value>
</valuemap>
<valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.2">
<value type="int" key="EnableQmlDebugging">0</value>
<value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/Volumes/Source/QT/build-QtSoundModem-Desktop_x86_darwin_generic_mach_o_64bit-Profile</value>
<value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory.shadowDir">/Volumes/Source/QT/build-QtSoundModem-Desktop_x86_darwin_generic_mach_o_64bit-Profile</value>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
<value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
<valuelist type="QVariantList" key="QtProjectManager.QMakeBuildStep.SelectedAbis"/>
</valuemap>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
</valuemap>
<value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Build</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
</valuemap>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
<value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
<value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
</valuemap>
<value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Clean</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
</valuemap>
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
<value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
<valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.CustomParsers"/>
<value type="bool" key="ProjectExplorer.BuildConfiguration.ParseStandardOutput">false</value>
<valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Profile</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
<value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">0</value>
<value type="int" key="QtQuickCompiler">0</value>
<value type="int" key="SeparateDebugInfo">0</value>
</valuemap>
<value type="qlonglong" key="ProjectExplorer.Target.BuildConfigurationCount">3</value>
<valuemap type="QVariantMap" key="ProjectExplorer.Target.DeployConfiguration.0">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
<value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">0</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Deploy</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Deploy</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Deploy</value>
</valuemap>
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">1</value>
<valuemap type="QVariantMap" key="ProjectExplorer.DeployConfiguration.CustomData"/>
<value type="bool" key="ProjectExplorer.DeployConfiguration.CustomDataEnabled">false</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.DefaultDeployConfiguration</value>
</valuemap>
<value type="qlonglong" key="ProjectExplorer.Target.DeployConfigurationCount">1</value>
<valuemap type="QVariantMap" key="ProjectExplorer.Target.RunConfiguration.0">
<value type="bool" key="Analyzer.Perf.Settings.UseGlobalSettings">true</value>
<value type="bool" key="Analyzer.QmlProfiler.Settings.UseGlobalSettings">true</value>
<value type="bool" key="Analyzer.Valgrind.Settings.UseGlobalSettings">true</value>
<valuelist type="QVariantList" key="CustomOutputParsers"/>
<value type="int" key="PE.EnvironmentAspect.Base">2</value>
<valuelist type="QVariantList" key="PE.EnvironmentAspect.Changes"/>
<value type="bool" key="PE.EnvironmentAspect.PrintOnRun">false</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4RunConfiguration:/Volumes/Source/QT/QtSoundModem/QtSoundModem.pro</value>
<value type="QString" key="ProjectExplorer.RunConfiguration.BuildKey">/Volumes/Source/QT/QtSoundModem/QtSoundModem.pro</value>
<value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value>
<value type="bool" key="RunConfiguration.UseLibrarySearchPath">true</value>
<value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value>
<value type="QString" key="RunConfiguration.WorkingDirectory.default">/Volumes/Source/QT/build-QtSoundModem-Desktop_x86_darwin_generic_mach_o_64bit-Debug/QtSoundModem.app/Contents/MacOS</value>
</valuemap>
<value type="qlonglong" key="ProjectExplorer.Target.RunConfigurationCount">1</value>
</valuemap>
</data>
<data>
<variable>ProjectExplorer.Project.TargetCount</variable>
<value type="qlonglong">1</value>
</data>
<data>
<variable>ProjectExplorer.Project.Updater.FileVersion</variable>
<value type="int">22</value>
</data>
<data>
<variable>Version</variable>
<value type="int">22</value>
</data>
</qtcreator>

64
QtSoundModem.pro~ Normal file
View File

@ -0,0 +1,64 @@
QT += core gui
QT += network
QT += serialport
greaterThan(QT_MAJOR_VERSION, 4): QT += widgets
TARGET = QtSoundModem
TEMPLATE = app
HEADERS += ./UZ7HOStuff.h \
./QtSoundModem.h \
./tcpCode.h
SOURCES += ./audio.c \
./pulse.c \
./ax25.c \
./ax25_demod.c \
./ax25_l2.c \
./ax25_mod.c \
./Config.cpp \
./kiss_mode.c \
./main.cpp \
./QtSoundModem.cpp \
./ShowFilter.cpp \
./SMMain.c \
./sm_main.c \
./UZ7HOUtils.c \
./ALSASound.c \
./ax25_agw.c \
./berlekamp.c \
./galois.c \
./rs.c \
./rsid.c \
./il2p.c \
./tcpCode.cpp \
./ax25_fec.c \
./RSUnit.c \
./ARDOPC.c \
./ardopSampleArrays.c \
./SoundInput.c \
./Modulate.c \
./ofdm.c \
./pktARDOP.c \
./BusyDetect.c \
./DW9600.c
FORMS += ./calibrateDialog.ui \
./devicesDialog.ui \
./filterWindow.ui \
./ModemDialog.ui \
./QtSoundModem.ui
RESOURCES += QtSoundModem.qrc
RC_ICONS = QtSoundModem.ico
QMAKE_CFLAGS += -g
#QMAKE_LFLAGS += -lasound -lpulse-simple -lpulse -lfftw3f
QMAKE_LIBS += -lasound -lfftw3f -ldl

View File

@ -382,6 +382,7 @@
</QtUic> </QtUic>
</ItemDefinitionGroup> </ItemDefinitionGroup>
<ItemGroup> <ItemGroup>
<ClCompile Include="6pack.cpp" />
<ClCompile Include="ARDOPC.c" /> <ClCompile Include="ARDOPC.c" />
<ClCompile Include="berlekamp.c" /> <ClCompile Include="berlekamp.c" />
<ClCompile Include="BusyDetect.c" /> <ClCompile Include="BusyDetect.c" />

View File

@ -140,6 +140,9 @@
<ClCompile Include="berlekamp.c"> <ClCompile Include="berlekamp.c">
<Filter>Generated Files</Filter> <Filter>Generated Files</Filter>
</ClCompile> </ClCompile>
<ClCompile Include="6pack.cpp">
<Filter>Source Files</Filter>
</ClCompile>
</ItemGroup> </ItemGroup>
<ItemGroup> <ItemGroup>
<QtMoc Include="QtSoundModem.h"> <QtMoc Include="QtSoundModem.h">

View File

@ -20,15 +20,15 @@
<DebuggerFlavor>WindowsLocalDebugger</DebuggerFlavor> <DebuggerFlavor>WindowsLocalDebugger</DebuggerFlavor>
</PropertyGroup> </PropertyGroup>
<PropertyGroup Label="QtSettings" Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'"> <PropertyGroup Label="QtSettings" Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
<QtLastBackgroundBuild>2024-06-21T13:50:20.1736205Z</QtLastBackgroundBuild> <QtLastBackgroundBuild>2024-10-02T12:37:32.3312444Z</QtLastBackgroundBuild>
</PropertyGroup> </PropertyGroup>
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|x64'" Label="QtSettings"> <PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|x64'" Label="QtSettings">
<QtLastBackgroundBuild>2024-06-21T13:50:20.3245934Z</QtLastBackgroundBuild> <QtLastBackgroundBuild>2024-10-02T12:37:32.7461423Z</QtLastBackgroundBuild>
</PropertyGroup> </PropertyGroup>
<PropertyGroup Label="QtSettings" Condition="'$(Configuration)|$(Platform)'=='Release|Win32'"> <PropertyGroup Label="QtSettings" Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
<QtLastBackgroundBuild>2024-06-21T13:50:20.4555992Z</QtLastBackgroundBuild> <QtLastBackgroundBuild>2024-10-02T12:37:33.4644113Z</QtLastBackgroundBuild>
</PropertyGroup> </PropertyGroup>
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|x64'" Label="QtSettings"> <PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|x64'" Label="QtSettings">
<QtLastBackgroundBuild>2024-06-21T13:50:20.6366033Z</QtLastBackgroundBuild> <QtLastBackgroundBuild>2024-10-02T12:37:33.9800504Z</QtLastBackgroundBuild>
</PropertyGroup> </PropertyGroup>
</Project> </Project>

View File

@ -29,6 +29,42 @@ along with QtSoundModem. If not, see http://www.gnu.org/licenses
#include <errno.h> #include <errno.h>
#include <stdint.h> #include <stdint.h>
void platformInit();
void RsCreate();
void detector_init();
void KISS_init();
void ax25_init();
void init_raduga();
void il2p_init(int il2p_debug);
void SoundFlush();
void BufferFull(short * Samples, int nSamples);
void PollReceivedSamples();
void chk_dcd1(int snd_ch, int buf_size);
void make_core_BPF(UCHAR snd_ch, short freq, short width);
void modulator(UCHAR snd_ch, int buf_size);
void sendAckModeAcks(int snd_ch);
void PktARDOPEncode(UCHAR * Data, int Len, int Chan);
void RUHEncode(unsigned char * Data, int Len, int chan);
void sendRSID(int Chan, int dropTX);
void SetupGPIOPTT();
int stricmp(const unsigned char * pStr1, const unsigned char *pStr2);
int gpioInitialise(void);
int OpenCOMPort(char * pPort, int speed, BOOL SetDTR, BOOL SetRTS, BOOL Quiet, int Stopbits);
void HAMLIBSetPTT(int PTTState);
void FLRigSetPTT(int PTTState);
void StartWatchdog();
void StopWatchdog();
void gpioWrite(unsigned gpio, unsigned level);
BOOL WriteCOMBlock(int fd, char * Block, int BytesToWrite);
void COMSetDTR(int fd);
void COMSetRTS(int fd);
void analiz_frame(int snd_ch, string * frame, char * code, boolean fecflag);
size_t write(int fd, void * buf, size_t count);
int close(int fd);
void SendMgmtPTT(int snd_ch, int PTTState);
BOOL KISSServ; BOOL KISSServ;
int KISSPort; int KISSPort;
@ -367,13 +403,13 @@ extern int intLastStop;
void SMSortSignals2(float * dblMag, int intStartBin, int intStopBin, int intNumBins, float * dblAVGSignalPerBin, float * dblAVGBaselinePerBin); void SMSortSignals2(float * dblMag, int intStartBin, int intStopBin, int intNumBins, float * dblAVGSignalPerBin, float * dblAVGBaselinePerBin);
BOOL SMBusyDetect3(float * dblMag, int intStart, int intStop) // this only called while searching for leader ...once leader detected, no longer called. BOOL SMBusyDetect3(int Chan, float * dblMag, int intStart, int intStop) // this only called while searching for leader ...once leader detected, no longer called.
{ {
// First sort signals and look at highes signals:baseline ratio.. // First sort signals and look at highes signals:baseline ratio..
float dblAVGSignalPerBinNarrow, dblAVGSignalPerBinWide, dblAVGBaselineNarrow, dblAVGBaselineWide; float dblAVGSignalPerBinNarrow, dblAVGSignalPerBinWide, dblAVGBaselineNarrow, dblAVGBaselineWide;
float dblSlowAlpha = 0.2f; float dblSlowAlpha = 0.2f;
float dblAvgStoNNarrow = 0, dblAvgStoNWide = 0; static float dblAvgStoNNarrow[4] = { 0 }, dblAvgStoNWide[4] = {0};
int intNarrow = 8; // 8 x 11.72 Hz about 94 z int intNarrow = 8; // 8 x 11.72 Hz about 94 z
int intWide = ((intStop - intStart) * 2) / 3; //* 0.66); int intWide = ((intStop - intStart) * 2) / 3; //* 0.66);
int blnBusy = FALSE; int blnBusy = FALSE;
@ -384,15 +420,16 @@ BOOL SMBusyDetect3(float * dblMag, int intStart, int intStop) // this onl
SMSortSignals2(dblMag, intStart, intStop, intNarrow, &dblAVGSignalPerBinNarrow, &dblAVGBaselineNarrow); SMSortSignals2(dblMag, intStart, intStop, intNarrow, &dblAVGSignalPerBinNarrow, &dblAVGBaselineNarrow);
// Shouldn't dblAvgStoNNarrow, dblAvgStoNWide be static ??????
if (intLastStart == intStart && intLastStop == intStop) if (intLastStart == intStart && intLastStop == intStop)
dblAvgStoNNarrow = (1 - dblSlowAlpha) * dblAvgStoNNarrow + dblSlowAlpha * dblAVGSignalPerBinNarrow / dblAVGBaselineNarrow; dblAvgStoNNarrow[Chan] = (1 - dblSlowAlpha) * dblAvgStoNNarrow[Chan] + dblSlowAlpha * dblAVGSignalPerBinNarrow / dblAVGBaselineNarrow;
else else
{ {
// This initializes the Narrow average after a bandwidth change // This initializes the Narrow average after a bandwidth change
dblAvgStoNNarrow = dblAVGSignalPerBinNarrow / dblAVGBaselineNarrow; dblAvgStoNNarrow[Chan] = dblAVGSignalPerBinNarrow / dblAVGBaselineNarrow;
intLastStart = intStart;
intLastStop = intStop;
} }
// Wide band (66% of current bandwidth) // Wide band (66% of current bandwidth)
@ -400,12 +437,12 @@ BOOL SMBusyDetect3(float * dblMag, int intStart, int intStop) // this onl
SMSortSignals2(dblMag, intStart, intStop, intWide, &dblAVGSignalPerBinWide, &dblAVGBaselineWide); SMSortSignals2(dblMag, intStart, intStop, intWide, &dblAVGSignalPerBinWide, &dblAVGBaselineWide);
if (intLastStart == intStart && intLastStop == intStop) if (intLastStart == intStart && intLastStop == intStop)
dblAvgStoNWide = (1 - dblSlowAlpha) * dblAvgStoNWide + dblSlowAlpha * dblAVGSignalPerBinWide / dblAVGBaselineWide; dblAvgStoNWide[Chan] = (1 - dblSlowAlpha) * dblAvgStoNWide[Chan] + dblSlowAlpha * dblAVGSignalPerBinWide / dblAVGBaselineWide;
else else
{ {
// This initializes the Wide average after a bandwidth change // This initializes the Wide average after a bandwidth change
dblAvgStoNWide = dblAVGSignalPerBinWide / dblAVGBaselineWide; dblAvgStoNWide[Chan] = dblAVGSignalPerBinWide / dblAVGBaselineWide;
intLastStart = intStart; intLastStart = intStart;
intLastStop = intStop; intLastStop = intStop;
} }
@ -413,7 +450,7 @@ BOOL SMBusyDetect3(float * dblMag, int intStart, int intStop) // this onl
// Preliminary calibration...future a function of bandwidth and BusyDet. // Preliminary calibration...future a function of bandwidth and BusyDet.
blnBusy = (dblAvgStoNNarrow > (3 + 0.008 * BusyDet4th)) || (dblAvgStoNWide > (5 + 0.02 * BusyDet4th)); blnBusy = (dblAvgStoNNarrow[Chan] > (3 + 0.008 * BusyDet4th)) || (dblAvgStoNWide[Chan] > (5 + 0.02 * BusyDet4th));
// if (BusyDet == 0) // if (BusyDet == 0)
// blnBusy = FALSE; // 0 Disables check ?? Is this the best place to do this? // blnBusy = FALSE; // 0 Disables check ?? Is this the best place to do this?
@ -452,7 +489,7 @@ void SMSortSignals2(float * dblMag, int intStartBin, int intStopBin, int intNumB
*dblAVGBaselinePerBin = dblSum2 / (intStopBin - intStartBin - intNumBins - 1); *dblAVGBaselinePerBin = dblSum2 / (intStopBin - intStartBin - intNumBins - 1);
} }
extern void updateDCD(int Chan, BOOL State);
void SMUpdateBusyDetector(int LR, float * Real, float *Imag) void SMUpdateBusyDetector(int LR, float * Real, float *Imag)
{ {
@ -465,10 +502,8 @@ void SMUpdateBusyDetector(int LR, float * Real, float *Imag)
static BOOL blnLastBusyStatus[4]; static BOOL blnLastBusyStatus[4];
float dblMagAvg = 0; float dblMagAvg = 0;
int intTuneLineLow, intTuneLineHi, intDelta;
int i, chan; int i, chan;
return;
if (Now - LastBusyCheck < 100) // ?? if (Now - LastBusyCheck < 100) // ??
return; return;
@ -487,6 +522,9 @@ void SMUpdateBusyDetector(int LR, float * Real, float *Imag)
Low = tx_freq[chan] - txbpf[chan] / 2; Low = tx_freq[chan] - txbpf[chan] / 2;
High = tx_freq[chan] + txbpf[chan] / 2; High = tx_freq[chan] + txbpf[chan] / 2;
// Low = tx_freq[chan] - 0.5*rx_shift[chan];
// High = tx_freq[chan] + 0.5*rx_shift[chan];
// BinSize is width of each fft bin in Hz // BinSize is width of each fft bin in Hz
Start = (Low / BinSize); // First and last bins to process Start = (Low / BinSize); // First and last bins to process
@ -499,20 +537,18 @@ void SMUpdateBusyDetector(int LR, float * Real, float *Imag)
dblMagAvg += dblMag[i]; dblMagAvg += dblMag[i];
} }
blnBusyStatus = SMBusyDetect3(dblMag, Start, End); blnBusyStatus = SMBusyDetect3(chan, dblMag, Start, End);
if (blnBusyStatus && !blnLastBusyStatus[chan]) if (blnBusyStatus && !blnLastBusyStatus[chan])
{ {
Debugprintf("Ch %d Busy True", chan); // Debugprintf("Ch %d Busy True", chan);
updateDCD(chan, TRUE);
} }
else if (blnLastBusyStatus[chan] && !blnBusyStatus) else if (blnLastBusyStatus[chan] && !blnBusyStatus)
{ {
Debugprintf("Ch %d Busy False", chan); // Debugprintf("Ch %d Busy False", chan);
updateDCD(chan, FALSE);
} }
// stcStatus.Text = "FALSE"
// queTNCStatus.Enqueue(stcStatus)
// 'Debug.WriteLine("BUSY FALSE @ " & Format(DateTime.UtcNow, "HH:mm:ss"))
blnLastBusyStatus[chan] = blnBusyStatus; blnLastBusyStatus[chan] = blnBusyStatus;
} }
} }
@ -1222,6 +1258,7 @@ void CM108_set_ptt(int PTTState)
float amplitudes[4] = { 32000, 32000, 32000, 32000 }; float amplitudes[4] = { 32000, 32000, 32000, 32000 };
extern float amplitude; extern float amplitude;
void startpttOnTimer(); void startpttOnTimer();
extern void UpdatePTTStats(int Chan, int State);
void RadioPTT(int snd_ch, BOOL PTTState) void RadioPTT(int snd_ch, BOOL PTTState)
{ {
@ -1240,6 +1277,15 @@ void RadioPTT(int snd_ch, BOOL PTTState)
StopWatchdog(); StopWatchdog();
} }
if ((PTTMode & PTTHOST))
{
// Send PTT ON/OFF to any mgmt connections
SendMgmtPTT(snd_ch, PTTState);
}
UpdatePTTStats(snd_ch, PTTState);
#ifdef __ARM_ARCH #ifdef __ARM_ARCH
if (useGPIO) if (useGPIO)
{ {
@ -1306,6 +1352,8 @@ void RadioPTT(int snd_ch, BOOL PTTState)
COMClearRTS(hPTTDevice); COMClearRTS(hPTTDevice);
} }
} }
startpttOnTimer(); startpttOnTimer();
} }

View File

@ -4,8 +4,8 @@
// My port of UZ7HO's Soundmodem // My port of UZ7HO's Soundmodem
// //
#define VersionString "0.0.0.72" #define VersionString "0.0.0.73"
#define VersionBytes {0, 0, 0, 72} #define VersionBytes {0, 0, 0, 73}
//#define LOGTX //#define LOGTX
//#define LOGRX //#define LOGRX
@ -181,7 +181,7 @@
// Improve reliability of waterfall update // Improve reliability of waterfall update
// Report and set fx.25 and il2p flags to/from BPQ // Report and set fx.25 and il2p flags to/from BPQ
// .72 Fix IL2P for RUH modems // .72 Fix IL2P for RUH modems // July 2024
// Fix crash when closing in non-gui mode // Fix crash when closing in non-gui mode
// Fix loop in chk_dcd1 // Fix loop in chk_dcd1
// Change method of timing PTT // Change method of timing PTT
@ -192,6 +192,11 @@
// Change phase map of QPSK3600 mode to match Nino TNC // Change phase map of QPSK3600 mode to match Nino TNC
//.73 Fix QPSK3600 RX Filters
// Add Mgmt Interface (Beta 2)
// Use ARDOP Busy detector (Beta 3)
// Various fixes to AGW interface (Beta 4)
// As far as I can see txtail is only there to make sure all bits get through the tx filter, // As far as I can see txtail is only there to make sure all bits get through the tx filter,
@ -317,6 +322,15 @@ typedef struct TKISSMode_t
} TKISSMode; } TKISSMode;
typedef struct MgmtMode_t
{
void * Socket; // Used as a key
char Msg[512]; // Received message
int Len;
int BPQPort[4]; // BPQ port for each modem
} TMgmtMode;
typedef struct TMChannel_t typedef struct TMChannel_t
{ {
@ -461,7 +475,7 @@ typedef struct AGWUser_t
{ {
void *socket; void *socket;
string * data_in; string * data_in;
TStringList AGW_frame_buf; // TStringList AGW_frame_buf;
boolean Monitor; boolean Monitor;
boolean Monitor_raw; boolean Monitor_raw;
boolean reportFreqAndModem; // Can report modem and frequency to host boolean reportFreqAndModem; // Can report modem and frequency to host
@ -534,6 +548,7 @@ typedef struct TAX25Port_t
#define PTTCM108 8 #define PTTCM108 8
#define PTTHAMLIB 16 #define PTTHAMLIB 16
#define PTTFLRIG 32 #define PTTFLRIG 32
#define PTTHOST 128 // May be combined with others
// Status flags // Status flags
@ -677,9 +692,9 @@ extern int SendSize;
#define MODEM_Q2400_BPF_TAP 256 //256 #define MODEM_Q2400_BPF_TAP 256 //256
#define MODEM_Q2400_LPF_TAP 128 //128 #define MODEM_Q2400_LPF_TAP 128 //128
// //
#define MODEM_Q3600_BPF 1800 #define MODEM_Q3600_BPF 3600
#define MODEM_Q3600_TXBPF 2000 #define MODEM_Q3600_TXBPF 3000
#define MODEM_Q3600_LPF 600 #define MODEM_Q3600_LPF 1350
#define MODEM_Q3600_BPF_TAP 256 #define MODEM_Q3600_BPF_TAP 256
#define MODEM_Q3600_LPF_TAP 128 #define MODEM_Q3600_LPF_TAP 128
// //
@ -1011,6 +1026,9 @@ extern int IPOLL[4];
extern int maxframe[4]; extern int maxframe[4];
extern int TXFrmMode[4]; extern int TXFrmMode[4];
extern int bytes[4];
extern int bytes2mins[4];
extern char MyDigiCall[4][512]; extern char MyDigiCall[4][512];
extern char exclude_callsigns[4][512]; extern char exclude_callsigns[4][512];
extern char exclude_APRS_frm[4][512]; extern char exclude_APRS_frm[4][512];

View File

@ -44,6 +44,11 @@ void printtick(char * msg);
void PollReceivedSamples(); void PollReceivedSamples();
short * SoundInit(); short * SoundInit();
void StdinPollReceivedSamples(); void StdinPollReceivedSamples();
extern void WriteDebugLog(char * Mess);
extern void UDPPollReceivedSamples();
extern void QSleep(int ms);
extern void ProcessNewSamples(short * Samples, int nSamples);
extern void sendSamplestoStdout(short * Samples, int nSamples);
#include <math.h> #include <math.h>
@ -57,7 +62,7 @@ void GetSoundDevices();
#define MaxReceiveSize 2048 // Enough for 9600 #define MaxReceiveSize 2048 // Enough for 9600
#define MaxSendSize 4096 #define MaxSendSize 4096
short buffer[2][MaxSendSize * 2]; // Two Transfer/DMA buffers of 0.1 Sec (x2 for Stereo) short buffer[4][MaxSendSize * 2]; // Two Transfer/DMA buffers of 0.1 Sec (x2 for Stereo)
short inbuffer[5][MaxReceiveSize * 2]; // Input Transfer/ buffers of 0.1 Sec (x2 for Stereo) short inbuffer[5][MaxReceiveSize * 2]; // Input Transfer/ buffers of 0.1 Sec (x2 for Stereo)
extern short * DMABuffer; extern short * DMABuffer;
@ -102,10 +107,12 @@ WAVEFORMATEX wfx = { WAVE_FORMAT_PCM, 2, 12000, 48000, 4, 16, 0 };
HWAVEOUT hWaveOut = 0; HWAVEOUT hWaveOut = 0;
HWAVEIN hWaveIn = 0; HWAVEIN hWaveIn = 0;
WAVEHDR header[2] = WAVEHDR header[4] =
{ {
{(char *)buffer[0], 0, 0, 0, 0, 0, 0, 0}, {(char *)buffer[0], 0, 0, 0, 0, 0, 0, 0},
{(char *)buffer[1], 0, 0, 0, 0, 0, 0, 0} {(char *)buffer[1], 0, 0, 0, 0, 0, 0, 0},
{(char *)buffer[2], 0, 0, 0, 0, 0, 0, 0},
{(char *)buffer[3], 0, 0, 0, 0, 0, 0, 0}
}; };
WAVEHDR inheader[5] = WAVEHDR inheader[5] =
@ -155,12 +162,6 @@ VOID __cdecl Debugprintf(const char * format, ...)
void platformInit() void platformInit()
{ {
TIMECAPS tc;
unsigned int wTimerRes;
DWORD t, lastt = 0;
int i = 0;
_strupr(CaptureDevice); _strupr(CaptureDevice);
_strupr(PlaybackDevice); _strupr(PlaybackDevice);
@ -224,20 +225,20 @@ FILE * wavfp1;
BOOL DMARunning = FALSE; // Used to start DMA on first write BOOL DMARunning = FALSE; // Used to start DMA on first write
BOOL SeeIfCardBusy()
{
if ((header[!Index].dwFlags & WHDR_DONE))
return 0;
return 1;
}
extern void sendSamplestoUDP(short * Samples, int nSamples, int Port); extern void sendSamplestoUDP(short * Samples, int nSamples, int Port);
extern int UDPClientPort; extern int UDPClientPort;
short * SendtoCard(unsigned short * buf, int n) short * SendtoCard(unsigned short * buf, int n)
{ {
int NextBuffer = Index;
char Msg[80];
NextBuffer++;
if (NextBuffer > 3)
NextBuffer = 0;
if (SoundMode == 3) // UDP if (SoundMode == 3) // UDP
{ {
sendSamplestoUDP(buf, n, UDPClientPort); sendSamplestoUDP(buf, n, UDPClientPort);
@ -256,15 +257,17 @@ short * SendtoCard(unsigned short * buf, int n)
waveOutPrepareHeader(hWaveOut, &header[Index], sizeof(WAVEHDR)); waveOutPrepareHeader(hWaveOut, &header[Index], sizeof(WAVEHDR));
waveOutWrite(hWaveOut, &header[Index], sizeof(WAVEHDR)); waveOutWrite(hWaveOut, &header[Index], sizeof(WAVEHDR));
// wait till previous buffer is complete // wait till next buffer is free
while (!(header[!Index].dwFlags & WHDR_DONE)) while (!(header[NextBuffer].dwFlags & WHDR_DONE))
{ {
txSleep(5); // Run buckground while waiting txSleep(5); // Run buckground while waiting
} }
waveOutUnprepareHeader(hWaveOut, &header[!Index], sizeof(WAVEHDR)); waveOutUnprepareHeader(hWaveOut, &header[NextBuffer], sizeof(WAVEHDR));
Index = !Index; Index = NextBuffer;
sprintf(Msg, "TX Buffer %d", NextBuffer);
return &buffer[Index][0]; return &buffer[Index][0];
} }
@ -365,7 +368,7 @@ int onlyMixSnoop = 0;
int InitSound(BOOL Report) int InitSound(BOOL Report)
{ {
int i, t, ret; int i, ret;
if (SoundMode == 4) if (SoundMode == 4)
{ {
@ -400,6 +403,8 @@ int InitSound(BOOL Report)
header[0].dwFlags = WHDR_DONE; header[0].dwFlags = WHDR_DONE;
header[1].dwFlags = WHDR_DONE; header[1].dwFlags = WHDR_DONE;
header[2].dwFlags = WHDR_DONE;
header[3].dwFlags = WHDR_DONE;
if (strlen(PlaybackDevice) <= 2) if (strlen(PlaybackDevice) <= 2)
PlayBackIndex = atoi(PlaybackDevice); PlayBackIndex = atoi(PlaybackDevice);
@ -723,11 +728,15 @@ void SoundFlush()
SendtoCard(buffer[Index], Number); SendtoCard(buffer[Index], Number);
// Wait for all sound output to complete // Wait for all sound output to complete
while (!(header[0].dwFlags & WHDR_DONE)) while (!(header[0].dwFlags & WHDR_DONE))
txSleep(10); txSleep(10);
while (!(header[1].dwFlags & WHDR_DONE)) while (!(header[1].dwFlags & WHDR_DONE))
txSleep(10); txSleep(10);
while (!(header[2].dwFlags & WHDR_DONE))
txSleep(10);
while (!(header[3].dwFlags & WHDR_DONE))
txSleep(10);
// I think we should turn round the link here. I dont see the point in // I think we should turn round the link here. I dont see the point in
// waiting for MainPoll // waiting for MainPoll
@ -922,6 +931,7 @@ BOOL WriteCOMBlock(HANDLE fd, char * Block, int BytesToWrite)
if ((!fWriteStat) || (BytesToWrite != BytesWritten)) if ((!fWriteStat) || (BytesToWrite != BytesWritten))
{ {
int Err = GetLastError(); int Err = GetLastError();
Debugprintf("Serial Write Error %d", Err);
ClearCommError(fd, &ErrorFlags, &ComStat); ClearCommError(fd, &ErrorFlags, &ComStat);
return FALSE; return FALSE;
} }

View File

@ -40,6 +40,7 @@
#endif #endif
void Debugprintf(const char * format, ...); void Debugprintf(const char * format, ...);
void Sleep(int mS);
extern int Closing; extern int Closing;

15
ax25.c
View File

@ -29,10 +29,20 @@ __declspec(dllimport) unsigned short __stdcall ntohs(__in unsigned short hostsho
#else #else
#include <stdint.h>
uint32_t htonl(uint32_t hostlong);
uint16_t htons(uint16_t hostshort);
uint32_t ntohl(uint32_t netlong);
uint16_t ntohs(uint16_t netshort);
#define strtok_s strtok_r #define strtok_s strtok_r
#include <stddef.h> #include <stddef.h>
#endif #endif
void set_DM(int snd_ch, Byte * path);
void rst_values(TAX25Port * AX25Sess);
void decode_frame(Byte * frame, int len, Byte * path, string * data, void decode_frame(Byte * frame, int len, Byte * path, string * data,
Byte * pid, Byte * nr, Byte * ns, Byte * f_type, Byte * f_id, Byte * pid, Byte * nr, Byte * ns, Byte * f_type, Byte * f_id,
Byte * rpt, Byte * pf, Byte * cr); Byte * rpt, Byte * pf, Byte * cr);
@ -244,6 +254,9 @@ int maxframe[4] = { 0,0,0,0 };
int TXFrmMode[4] = { 0,0,0,0 }; int TXFrmMode[4] = { 0,0,0,0 };
int max_frame_collector[4] = { 0,0,0,0 }; int max_frame_collector[4] = { 0,0,0,0 };
int bytes[4] = { 0,0,0,0 };
int bytes2mins[4] = { 0,0,0,0 };
char MyDigiCall[4][512] = { "","","","" }; char MyDigiCall[4][512] = { "","","","" };
char exclude_callsigns[4][512] = { "","","","" }; char exclude_callsigns[4][512] = { "","","","" };
char exclude_APRS_frm[4][512] = { "","","","" }; char exclude_APRS_frm[4][512] = { "","","","" };
@ -1729,7 +1742,7 @@ int is_excluded_frm(int snd_ch, int f_id, string * data)
int number_digi(string path) int number_digi(char * path)
{ {
int n = 0; int n = 0;

View File

@ -177,7 +177,7 @@ void AGW_del_socket(void * socket)
if (AGW == NULL) if (AGW == NULL)
return; return;
Clear(&AGW->AGW_frame_buf); // Clear(&AGW->AGW_frame_buf);
freeString(AGW->data_in); freeString(AGW->data_in);
AGW->Monitor = 0; AGW->Monitor = 0;
AGW->Monitor_raw = 0; AGW->Monitor_raw = 0;
@ -190,9 +190,7 @@ void AGW_add_socket(void * socket)
{ {
AGWUser * User = (struct AGWUser_t *)malloc(sizeof(struct AGWUser_t)); // One Client AGWUser * User = (struct AGWUser_t *)malloc(sizeof(struct AGWUser_t)); // One Client
AGWUsers = realloc(AGWUsers, (AGWConCount + 1) * sizeof(void *)); AGWUsers = realloc(AGWUsers, (AGWConCount + 1) * sizeof(void *));
AGWUsers[AGWConCount++] = User; AGWUsers[AGWConCount++] = User;
User->data_in = newString(); User->data_in = newString();
@ -259,7 +257,7 @@ string * AGW_R_Frame()
string * AGW_X_Frame(char * CallFrom, UCHAR reg_call) string * AGW_X_Frame(char * CallFrom, UCHAR reg_call)
{ {
string * Msg = AGW_frame_header(0, 'x', 0, CallFrom, "", 1); string * Msg = AGW_frame_header(0, 'X', 0, CallFrom, "", 1);
stringAdd(Msg, (UCHAR *)&reg_call, 1); stringAdd(Msg, (UCHAR *)&reg_call, 1);
@ -276,13 +274,16 @@ string * AGW_G_Frame()
for (int i = 0; i < 4; i++) for (int i = 0; i < 4; i++)
{ {
Ports[0]++;
if (soundChannel[i]) if (soundChannel[i])
{
Ports[0]++;
sprintf(portMsg, "Port%c with SoundCard Ch %c;", Ports[0], 'A' + i); sprintf(portMsg, "Port%c with SoundCard Ch %c;", Ports[0], 'A' + i);
else strcat(Ports, portMsg);
sprintf(portMsg, "Port%c Disabled;", Ports[0]); }
// else
// sprintf(portMsg, "Port%c Disabled;", Ports[0]);
strcat(Ports, portMsg); ;
} }
@ -294,7 +295,6 @@ string * AGW_G_Frame()
}; };
string * AGW_Gs_Frame(int port, Byte * port_info, int Len) string * AGW_Gs_Frame(int port, Byte * port_info, int Len)
{ {
string * Msg; string * Msg;
@ -511,12 +511,50 @@ void on_AGW_R_frame(AGWUser * AGW)
int refreshModems = 0; int refreshModems = 0;
/*
+ 00 On air baud rate(0 = 1200 / 1 = 2400 / 2 = 4800 / 3 = 9600)
+ 01 Traffic level(if 0xFF the port is not in autoupdate mode)
+ 02 TX Delay
+ 03 TX Tail
+ 04 Persist
+ 05 SlotTime
+ 06 MaxFrame
+ 07 How Many connections are active on this port
+ 08 LSB Low Word
+ 09 MSB Low Word
+ 10 LSB High Word
+ 11 MSB High Word HowManyBytes(received in the last 2 minutes) as a 32 bits(4 bytes) integer.Updated every two minutes.
*/
void on_AGW_Gs_frame(AGWUser * AGW, struct AGWHeader * Frame, Byte * Data) void on_AGW_Gs_frame(AGWUser * AGW, struct AGWHeader * Frame, Byte * Data)
{ {
// QTSM with a data field is used by QtSM to set/read Modem Params // QTSM with a data field is used by QtSM to set/read Modem Params
Byte info[48] = { 0, 255, 24, 3, 100, 15, 6, 0, 1, 0, 0, 0 }; //QTSM Signature Byte info[48] = { 0, 255, 24, 3, 100, 15, 6, 0, 1, 0, 0, 0 }; //QTSM Signature
int Len = 12; int Len = 12;
int Port = Frame->Port;
// KD6YAM wants the info to be correct. BPQ used 24, 3, 100 as a signature but could use the Version.
// For now I'll fill in the rest
info[2] = txdelay[Port] / 10;
info[3] = txtail[Port] / 10;
info[4] = persist[Port];
info[5] = slottime[Port];
info[6] = maxframe[Port];
info[7] = 0;
int i = 0;
while (i < port_num)
{
if (AX25Port[Port][i].status != STAT_NO_LINK)
info[7]++;
i++;
}
memcpy(&info[8], &bytes2mins[Port], 4);
if (Frame->DataLength == 32) if (Frame->DataLength == 32)
{ {
@ -1360,7 +1398,6 @@ void AGW_Report_Modem_Change(int port)
int i; int i;
AGWUser * AGW; AGWUser * AGW;
string * pkt;
if (soundChannel[port] == 0) // Not in use if (soundChannel[port] == 0) // Not in use
return; return;
@ -1537,3 +1574,16 @@ void AGW_frame_analiz(AGWUser * AGW)
Debugprintf("AGW %c", Frame->DataKind); Debugprintf("AGW %c", Frame->DataKind);
} }
} }
void doAGW2MinTimer()
{
for (int n = 0; n < 4; n++)
{
if (soundChannel[n] == 0) // Channel not used
continue;
bytes2mins[n] = bytes[n];
bytes[n] = 0;
}
}

View File

@ -27,6 +27,14 @@ extern word MEMRecovery[5];
void make_rx_frame_FX25(int snd_ch, int rcvr_nr, int emph, string * data); void make_rx_frame_FX25(int snd_ch, int rcvr_nr, int emph, string * data);
string * memory_ARQ(TStringList * buf, string * data); string * memory_ARQ(TStringList * buf, string * data);
void CreateStringList(TStringList * List);
void analiz_frame(int snd_ch, string * frame, char * code, boolean fecflag);
void KISS_on_data_out(int port, string * frame, int TX);
void updateDCD(int Chan, boolean State);
void Frame_Optimize(TAX25Port * AX25Sess, TStringList * buf);
void RX2TX(int snd_ch);
int fx25_decode_rs(Byte * data, int * eras_pos, int no_eras, int pad, int rs_size);
void il2p_rec_bit(int chan, int subchan, int slice, int dbit);
float GuessCentreFreq(int i); float GuessCentreFreq(int i);
void ProcessRXFrames(int snd_ch); void ProcessRXFrames(int snd_ch);
@ -374,6 +382,7 @@ void chk_dcd1(int snd_ch, int buf_size)
if (lastDCDState[snd_ch] != dcd_bit_sync[snd_ch]) if (lastDCDState[snd_ch] != dcd_bit_sync[snd_ch])
{ {
updateDCD(snd_ch, dcd_bit_sync[snd_ch]);
updateDCD(snd_ch, dcd_bit_sync[snd_ch]); updateDCD(snd_ch, dcd_bit_sync[snd_ch]);
lastDCDState[snd_ch] = dcd_bit_sync[snd_ch]; lastDCDState[snd_ch] = dcd_bit_sync[snd_ch];
} }
@ -4258,7 +4267,7 @@ void ProcessRXFrames(int snd_ch)
// Work out which decoder and which emph settings worked. // Work out which decoder and which emph settings worked.
if (snd_ch < 0 || snd_ch >3) if (snd_ch < 0 || snd_ch > 3)
return; return;
if (detect_list[snd_ch].Count > 0) // no point if nothing decoded if (detect_list[snd_ch].Count > 0) // no point if nothing decoded

View File

@ -28,6 +28,16 @@ extern int RSID_SetModem[4];
extern int needRSID[4]; extern int needRSID[4];
extern int needRSID[4]; extern int needRSID[4];
BOOL useKISSControls = 0;
#define FEND 0xc0
#define FESC 0xDB
#define TFEND 0xDC
#define TFESC 0xDD
#define KISS_ACKMODE 0x0C
#define KISS_DATA 0
#define QTSMKISSCMD 7
/* /*
@ -60,6 +70,23 @@ string * make_frame(string * data, Byte * path, Byte pid, Byte nr, Byte ns, Byt
void rst_t3(TAX25Port * AX25Sess); void rst_t3(TAX25Port * AX25Sess);
TAX25Port * get_user_port(int snd_ch, Byte * path); TAX25Port * get_user_port(int snd_ch, Byte * path);
void analiz_frame(int snd_ch, string * frame, char * code, boolean fecflag);
boolean is_last_digi(Byte *path);
int is_excluded_call(int snd_ch, unsigned char * path);
boolean is_correct_path(Byte * path, Byte pid);
void KISS_on_data_out(int port, string * frame, int TX);
void ax25_info_init(TAX25Port * AX25Sess);
void clr_frm_win(TAX25Port * AX25Sess);
void decode_frame(Byte * frame, int len, Byte * path, string * data,
Byte * pid, Byte * nr, Byte * ns, Byte * f_type, Byte * f_id,
Byte * rpt, Byte * pf, Byte * cr);
void ax25_info_init(TAX25Port * AX25Sess);
void AGW_AX25_disc(TAX25Port * AX25Sess, Byte mode);
void AGW_AX25_conn(TAX25Port * AX25Sess, int snd_ch, Byte mode);
int number_digi(char * path);
void AGW_AX25_data_in(void * socket, int snd_ch, int PID, Byte * path, string * data);
void inc_frack(TAX25Port * AX25Sess) void inc_frack(TAX25Port * AX25Sess)
{ {
@ -1100,7 +1127,8 @@ void on_FRMR(void * socket, TAX25Port * AX25Sess, Byte * path)
{ {
AX25Sess->info.stat_end_ses = time(NULL); AX25Sess->info.stat_end_ses = time(NULL);
AGW_AX25_disc(socket, AX25Sess->snd_ch, MODE_OTHER, path); AGW_AX25_disc(AX25Sess, MODE_OTHER);
write_ax25_info(AX25Sess); write_ax25_info(AX25Sess);
} }
@ -1408,14 +1436,18 @@ void analiz_frame(int snd_ch, string * frame, char * code, boolean fecflag)
if (len < PKT_ERR) if (len < PKT_ERR)
return; return;
bytes[snd_ch] += frame->Length; // For AGW stats
if (AGWServ)
AGW_AX25_frame_analiz(snd_ch, TRUE, frame);
decode_frame(frame->Data, frame->Length, path, data, &pid, &nr, &ns, &f_type, &f_id, &rpt, &pf, &cr); decode_frame(frame->Data, frame->Length, path, data, &pid, &nr, &ns, &f_type, &f_id, &rpt, &pf, &cr);
if (is_excluded_call(snd_ch, path)) if (is_excluded_call(snd_ch, path))
excluded =TRUE; excluded = TRUE;
// if is_excluded_frm(snd_ch,f_id,data) then excluded:=TRUE; // if is_excluded_frm(snd_ch,f_id,data) then excluded:=TRUE;
if (excluded) if (excluded)
return; return;
@ -1448,7 +1480,20 @@ void analiz_frame(int snd_ch, string * frame, char * code, boolean fecflag)
AGW_Raw_monitor(snd_ch, frame); AGW_Raw_monitor(snd_ch, frame);
if (KISSServ) if (KISSServ)
{
if (useKISSControls)
{
// Send a KISS Control frame with frame stats before data frame
int len = strlen(code);
UCHAR * Control = (UCHAR *)malloc(64);
len = sprintf(Control, "%c%cPKTINFO [%s]%c", FEND, (snd_ch) << 4 | QTSMKISSCMD, code, FEND);
KISSSendtoServer(NULL, Control, len);
}
KISS_on_data_out(snd_ch, frame, 0); KISS_on_data_out(snd_ch, frame, 0);
}
} }
// Digipeat frame // Digipeat frame
@ -1618,9 +1663,6 @@ void analiz_frame(int snd_ch, string * frame, char * code, boolean fecflag)
on_FRMR(socket, AX25Sess, path); on_FRMR(socket, AX25Sess, path);
break; break;
} }
if (AGWServ)
AGW_AX25_frame_analiz(snd_ch, TRUE, frame);
} }

View File

@ -25,6 +25,17 @@ along with QtSoundModem. If not, see http://www.gnu.org/licenses
// I assume this modulates (and sends?} frames // I assume this modulates (and sends?} frames
void InitBuffers();
void EncodeRS(Byte * xData, Byte * xEncoded);
void scrambler(UCHAR * in_buf, int Len);
void fx25_encode_rs(Byte * data, Byte *parity, int pad, int rs_size);
int fx25_decode_rs(Byte * data, int * eras_pos, int no_eras, int pad, int rs_size);
int il2p_get_new_bit_tail(UCHAR snd_ch, UCHAR bit);
int il2p_get_new_bit(int snd_ch, Byte bit);
int ARDOPSendToCard(int Chan, int Len);
void Flush();
void SampleSink(int LR, short Sample);
int RSEncode(UCHAR * bytToRS, UCHAR * RSBytes, int DataLen, int RSLen); int RSEncode(UCHAR * bytToRS, UCHAR * RSBytes, int DataLen, int RSLen);
//unit ax25_mod; //unit ax25_mod;

View File

@ -7,7 +7,7 @@
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>270</width> <width>270</width>
<height>411</height> <height>453</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
@ -276,6 +276,19 @@
</property> </property>
</widget> </widget>
</widget> </widget>
<widget class="QPushButton" name="Cal1500">
<property name="geometry">
<rect>
<x>66</x>
<y>416</y>
<width>139</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>10 secs 1500Hz Tone</string>
</property>
</widget>
</widget> </widget>
<resources/> <resources/>
<connections/> <connections/>

View File

@ -1,12 +1,12 @@
#define _MSC_EXTENSIONS #define _MSC_EXTENSIONS
#define _INTEGRAL_MAX_BITS 64 #define _INTEGRAL_MAX_BITS 64
#define _MSC_VER 1916 #define _MSC_VER 1916
#define _MSC_FULL_VER 191627051 #define _MSC_FULL_VER 191627051
#define _MSC_BUILD 0 #define _MSC_BUILD 0
#define _WIN32 #define _WIN32
#define _M_IX86 600 #define _M_IX86 600
#define _M_IX86_FP 2 #define _M_IX86_FP 2
#define _CPPRTTI #define _CPPRTTI
#define _DEBUG #define _DEBUG
#define _MT #define _MT
#define _DLL #define _DLL

View File

@ -1,12 +1,12 @@
#define _MSC_EXTENSIONS #define _MSC_EXTENSIONS
#define _INTEGRAL_MAX_BITS 64 #define _INTEGRAL_MAX_BITS 64
#define _MSC_VER 1916 #define _MSC_VER 1916
#define _MSC_FULL_VER 191627043 #define _MSC_FULL_VER 191627043
#define _MSC_BUILD 0 #define _MSC_BUILD 0
#define _WIN32 #define _WIN32
#define _M_IX86 600 #define _M_IX86 600
#define _M_IX86_FP 2 #define _M_IX86_FP 2
#define _CPPRTTI #define _CPPRTTI
#define _DEBUG #define _DEBUG
#define _MT #define _MT
#define _DLL #define _DLL

View File

@ -1,12 +1,12 @@
#define _MSC_EXTENSIONS #define _MSC_EXTENSIONS
#define _INTEGRAL_MAX_BITS 64 #define _INTEGRAL_MAX_BITS 64
#define _MSC_VER 1916 #define _MSC_VER 1916
#define _MSC_FULL_VER 191627043 #define _MSC_FULL_VER 191627043
#define _MSC_BUILD 0 #define _MSC_BUILD 0
#define _WIN32 #define _WIN32
#define _M_IX86 600 #define _M_IX86 600
#define _M_IX86_FP 2 #define _M_IX86_FP 2
#define _CPPRTTI #define _CPPRTTI
#define _DEBUG #define _DEBUG
#define _MT #define _MT
#define _DLL #define _DLL

View File

@ -1,7 +1,7 @@
#define _MSC_EXTENSIONS #define _MSC_EXTENSIONS
#define _INTEGRAL_MAX_BITS 64 #define _INTEGRAL_MAX_BITS 64
#define _MSC_VER 1916 #define _MSC_VER 1916
#define _MSC_FULL_VER 191627045 #define _MSC_FULL_VER 191627043
#define _MSC_BUILD 0 #define _MSC_BUILD 0
#define _WIN32 #define _WIN32
#define _M_IX86 600 #define _M_IX86 600

View File

@ -6,8 +6,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>535</width> <width>528</width>
<height>698</height> <height>721</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
@ -20,9 +20,9 @@
<property name="geometry"> <property name="geometry">
<rect> <rect>
<x>5</x> <x>5</x>
<y>10</y> <y>0</y>
<width>512</width> <width>513</width>
<height>671</height> <height>711</height>
</rect> </rect>
</property> </property>
<property name="verticalScrollBarPolicy"> <property name="verticalScrollBarPolicy">
@ -40,7 +40,7 @@
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>508</width> <width>508</width>
<height>668</height> <height>706</height>
</rect> </rect>
</property> </property>
<widget class="QGroupBox" name="groupBox"> <widget class="QGroupBox" name="groupBox">
@ -49,7 +49,7 @@
<x>5</x> <x>5</x>
<y>10</y> <y>10</y>
<width>541</width> <width>541</width>
<height>331</height> <height>361</height>
</rect> </rect>
</property> </property>
<property name="title"> <property name="title">
@ -582,14 +582,27 @@
<string>Only Mix/Snoop Devices (needs custom .asoundrc)</string> <string>Only Mix/Snoop Devices (needs custom .asoundrc)</string>
</property> </property>
</widget> </widget>
<widget class="QCheckBox" name="useKISSControls">
<property name="geometry">
<rect>
<x>20</x>
<y>328</y>
<width>271</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Enable KISS Control and Reporting</string>
</property>
</widget>
</widget> </widget>
<widget class="QGroupBox" name="groupBox_2"> <widget class="QGroupBox" name="Goup">
<property name="geometry"> <property name="geometry">
<rect> <rect>
<x>10</x> <x>10</x>
<y>360</y> <y>380</y>
<width>481</width> <width>481</width>
<height>101</height> <height>133</height>
</rect> </rect>
</property> </property>
<property name="title"> <property name="title">
@ -600,7 +613,7 @@
<rect> <rect>
<x>22</x> <x>22</x>
<y>24</y> <y>24</y>
<width>121</width> <width>129</width>
<height>18</height> <height>18</height>
</rect> </rect>
</property> </property>
@ -633,7 +646,7 @@
<rect> <rect>
<x>22</x> <x>22</x>
<y>48</y> <y>48</y>
<width>111</width> <width>131</width>
<height>18</height> <height>18</height>
</rect> </rect>
</property> </property>
@ -718,7 +731,7 @@
<rect> <rect>
<x>20</x> <x>20</x>
<y>74</y> <y>74</y>
<width>111</width> <width>135</width>
<height>18</height> <height>18</height>
</rect> </rect>
</property> </property>
@ -726,12 +739,97 @@
<string>UDP Sound Server Host</string> <string>UDP Sound Server Host</string>
</property> </property>
</widget> </widget>
<widget class="QComboBox" name="SixPackSerial">
<property name="geometry">
<rect>
<x>160</x>
<y>100</y>
<width>81</width>
<height>20</height>
</rect>
</property>
<property name="editable">
<bool>true</bool>
</property>
</widget>
<widget class="QLabel" name="label_17">
<property name="geometry">
<rect>
<x>20</x>
<y>98</y>
<width>111</width>
<height>18</height>
</rect>
</property>
<property name="text">
<string>6Pack Serial Port</string>
</property>
</widget>
<widget class="QLineEdit" name="SixPackTCP">
<property name="geometry">
<rect>
<x>320</x>
<y>100</y>
<width>47</width>
<height>20</height>
</rect>
</property>
</widget>
<widget class="QLabel" name="label_7">
<property name="geometry">
<rect>
<x>252</x>
<y>101</y>
<width>63</width>
<height>18</height>
</rect>
</property>
<property name="text">
<string>TCP Port</string>
</property>
</widget>
<widget class="QCheckBox" name="SixPackEnable">
<property name="geometry">
<rect>
<x>380</x>
<y>99</y>
<width>70</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Enabled</string>
</property>
</widget>
<widget class="QLineEdit" name="MgmtPort">
<property name="geometry">
<rect>
<x>410</x>
<y>25</y>
<width>47</width>
<height>20</height>
</rect>
</property>
</widget>
<widget class="QLabel" name="label_18">
<property name="geometry">
<rect>
<x>340</x>
<y>25</y>
<width>91</width>
<height>20</height>
</rect>
</property>
<property name="text">
<string>Mgmt Port</string>
</property>
</widget>
</widget> </widget>
<widget class="QGroupBox" name="groupBox_3"> <widget class="QGroupBox" name="groupBox_3">
<property name="geometry"> <property name="geometry">
<rect> <rect>
<x>10</x> <x>10</x>
<y>470</y> <y>520</y>
<width>481</width> <width>481</width>
<height>151</height> <height>151</height>
</rect> </rect>
@ -933,8 +1031,8 @@
<widget class="QWidget" name="layoutWidget"> <widget class="QWidget" name="layoutWidget">
<property name="geometry"> <property name="geometry">
<rect> <rect>
<x>140</x> <x>130</x>
<y>626</y> <y>670</y>
<width>215</width> <width>215</width>
<height>33</height> <height>33</height>
</rect> </rect>

4
il2p.c
View File

@ -88,7 +88,7 @@ void Debugprintf(const char * format, ...);
int SMUpdatePhaseConstellation(int chan, float * Phases, float * Mags, int intPSKPhase, int Count); int SMUpdatePhaseConstellation(int chan, float * Phases, float * Mags, int intPSKPhase, int Count);
extern int openTraceLog(); extern int openTraceLog();
extern uint64_t writeTraceLog(char * Data, char Dirn); extern uint64_t writeTraceLog(char * Data);
extern void closeTraceLog(); extern void closeTraceLog();
#define MAX_ADEVS 3 #define MAX_ADEVS 3
@ -4839,7 +4839,7 @@ void debugHexDump(unsigned char * Data, int Len, char Dirn)
Line[Len * 3] = 10; Line[Len * 3] = 10;
Line[Len * 3 + 1] = 0; Line[Len * 3 + 1] = 0;
} }
writeTraceLog(Line, Dirn); writeTraceLog(Line);
Data += 16; Data += 16;
Len -= 16; Len -= 16;

View File

@ -22,6 +22,8 @@ along with QtSoundModem. If not, see http://www.gnu.org/licenses
#include "UZ7HOStuff.h" #include "UZ7HOStuff.h"
int add_raw_frames(int snd_ch, string * frame, TStringList * buf);
// I think I need a struct for each connection, but a simple array of entries should be fine // I think I need a struct for each connection, but a simple array of entries should be fine
// My normal ** and count system // My normal ** and count system
// Each needs an input buffer of max size kiss frame and length (or maybe string is a good idea) // Each needs an input buffer of max size kiss frame and length (or maybe string is a good idea)
@ -35,6 +37,7 @@ int KISSConCount = 0;
#define TFESC 0xDD #define TFESC 0xDD
#define KISS_ACKMODE 0x0C #define KISS_ACKMODE 0x0C
#define KISS_DATA 0 #define KISS_DATA 0
#define QTSMKISSCMD 7
struct TKISSMode_t KISS; struct TKISSMode_t KISS;
@ -75,7 +78,7 @@ end;
void KISS_add_stream(void * Socket) void KISS_add_stream(void * Socket)
{ {
// Add a new connection. Called wheKISSn QT accepts an incoming call} // Add a new connection. Called when QT accepts an incoming call}
TKISSMode * KISS; TKISSMode * KISS;

View File

@ -33,15 +33,18 @@ extern void saveSettings();
extern int Closing; extern int Closing;
workerThread *t; workerThread *t;
serialThread *serial;
mynet m1; mynet m1;
QCoreApplication * a; QCoreApplication * a;
QtSoundModem * w; QtSoundModem * w;
int main(int argc, char *argv[]) int main(int argc, char *argv[])
{ {
char Title[128]; char Title[128];
QString Response;
if (argc > 1 && strcmp(argv[1], "nogui") == 0) if (argc > 1 && strcmp(argv[1], "nogui") == 0)
nonGUIMode = 1; nonGUIMode = 1;
@ -78,6 +81,7 @@ int main(int argc, char *argv[])
QObject::connect(&m1, SIGNAL(HLSetPTT(int)), &m1, SLOT(doHLSetPTT(int)), Qt::QueuedConnection); QObject::connect(&m1, SIGNAL(HLSetPTT(int)), &m1, SLOT(doHLSetPTT(int)), Qt::QueuedConnection);
QObject::connect(&m1, SIGNAL(FLRigSetPTT(int)), &m1, SLOT(doFLRigSetPTT(int)), Qt::QueuedConnection); QObject::connect(&m1, SIGNAL(FLRigSetPTT(int)), &m1, SLOT(doFLRigSetPTT(int)), Qt::QueuedConnection);
QObject::connect(&m1, SIGNAL(mgmtSetPTT(int, int)), &m1, SLOT(domgmtSetPTT(int, int)), Qt::QueuedConnection);
QObject::connect(&m1, SIGNAL(startTimer(int)), &m1, SLOT(dostartTimer(int)), Qt::QueuedConnection); QObject::connect(&m1, SIGNAL(startTimer(int)), &m1, SLOT(dostartTimer(int)), Qt::QueuedConnection);

1
ofdm.c
View File

@ -200,6 +200,7 @@ extern int LastDataFrameType; // Last data frame processed (for Memory ARQ, et
extern int intNAKctr; extern int intNAKctr;
extern int intACKctr; extern int intACKctr;
extern int intTimeouts; extern int intTimeouts;
void ARDOPSampleSink(short Sample);
extern UCHAR goodReceivedBlocks[128]; extern UCHAR goodReceivedBlocks[128];
extern UCHAR goodReceivedBlockLen[128]; extern UCHAR goodReceivedBlockLen[128];

File diff suppressed because it is too large Load Diff

View File

@ -18,6 +18,7 @@ along with QtSoundModem. If not, see http://www.gnu.org/licenses
*/ */
// UZ7HO Soundmodem Port by John Wiseman G8BPQ // UZ7HO Soundmodem Port by John Wiseman G8BPQ
#include <QMessageBox> #include <QMessageBox>
@ -27,15 +28,26 @@ along with QtSoundModem. If not, see http://www.gnu.org/licenses
#define CONNECT(sndr, sig, rcvr, slt) connect(sndr, SIGNAL(sig), rcvr, SLOT(slt)) #define CONNECT(sndr, sig, rcvr, slt) connect(sndr, SIGNAL(sig), rcvr, SLOT(slt))
QList<QTcpSocket*> _MgmtSockets;
QList<QTcpSocket*> _KISSSockets; QList<QTcpSocket*> _KISSSockets;
QList<QTcpSocket*> _AGWSockets; QList<QTcpSocket*> _AGWSockets;
QTcpServer * _KISSserver; QTcpServer * _KISSserver;
QTcpServer * _AGWserver; QTcpServer * _AGWserver;
QTcpServer * SixPackServer;
QTcpSocket *SixPackSocket;
QTcpServer * _MgmtServer;
TMgmtMode ** MgmtConnections = NULL;
int MgmtConCount = 0;
extern workerThread *t; extern workerThread *t;
extern mynet m1; extern mynet m1;
extern serialThread *serial;
QString Response;
extern int MgmtPort;
extern "C" int KISSPort; extern "C" int KISSPort;
extern "C" void * initPulse(); extern "C" void * initPulse();
extern "C" int SoundMode; extern "C" int SoundMode;
@ -44,6 +56,10 @@ extern "C" int UDPClientPort;
extern "C" int UDPServerPort; extern "C" int UDPServerPort;
extern "C" int TXPort; extern "C" int TXPort;
extern char SixPackDevice[256];
extern int SixPackPort;
extern int SixPackEnable;
char UDPHost[64] = ""; char UDPHost[64] = "";
int UDPServ = 0; // UDP Server Active (ie broadcast sound frams as UDP packets) int UDPServ = 0; // UDP Server Active (ie broadcast sound frams as UDP packets)
@ -68,9 +84,10 @@ extern "C"
void MainLoop(); void MainLoop();
void set_speed(int snd_ch, int Modem); void set_speed(int snd_ch, int Modem);
void init_speed(int snd_ch); void init_speed(int snd_ch);
} }
void Process6PackData(unsigned char * Bytes, int Len);
extern "C" int nonGUIMode; extern "C" int nonGUIMode;
QTimer *timer; QTimer *timer;
@ -121,12 +138,56 @@ void mynet::start()
} }
} }
if (MgmtPort)
{
_MgmtServer = new(QTcpServer);
if (_MgmtServer->listen(QHostAddress::Any, MgmtPort))
connect(_MgmtServer, SIGNAL(newConnection()), this, SLOT(onMgmtConnection()));
else
{
if (nonGUIMode)
Debugprintf("Listen failed for Mgmt Port");
else
{
QMessageBox msgBox;
msgBox.setText("Listen failed for Mgmt Port.");
msgBox.exec();
}
}
}
QObject::connect(t, SIGNAL(sendtoKISS(void *, unsigned char *, int)), this, SLOT(sendtoKISS(void *, unsigned char *, int)), Qt::QueuedConnection); QObject::connect(t, SIGNAL(sendtoKISS(void *, unsigned char *, int)), this, SLOT(sendtoKISS(void *, unsigned char *, int)), Qt::QueuedConnection);
QTimer *timer = new QTimer(this); QTimer *timer = new QTimer(this);
connect(timer, SIGNAL(timeout()), this, SLOT(MyTimerSlot())); connect(timer, SIGNAL(timeout()), this, SLOT(MyTimerSlot()));
timer->start(100); timer->start(100);
if (SixPackEnable)
{
if (SixPackDevice[0] && strcmp(SixPackDevice, "None") != 0) // Using serial
{
serial->startSlave(SixPackDevice, 30000, Response);
serial->start();
// connect(serial, &serialThread::request, this, &QtSoundModem::showRequest);
// connect(serial, &serialThread::error, this, &QtSoundModem::processError);
// connect(serial, &serialThread::timeout, this, &QtSoundModem::processTimeout);
}
else if (SixPackPort) // using TCP
{
SixPackServer = new(QTcpServer);
if (SixPackServer->listen(QHostAddress::Any, SixPackPort))
connect(SixPackServer, SIGNAL(newConnection()), this, SLOT(on6PackConnection()));
}
}
} }
void mynet::MyTimerSlot() void mynet::MyTimerSlot()
@ -172,6 +233,32 @@ void mynet::onAGWReadyRead()
AGW_explode_frame(sender, datas.data(), datas.length()); AGW_explode_frame(sender, datas.data(), datas.length());
} }
void mynet::on6PackReadyRead()
{
QTcpSocket* sender = static_cast<QTcpSocket*>(QObject::sender());
QByteArray datas = sender->readAll();
Process6PackData((unsigned char *)datas.data(), datas.length());
}
void mynet::on6PackSocketStateChanged(QAbstractSocket::SocketState socketState)
{
if (socketState == QAbstractSocket::UnconnectedState)
{
QTcpSocket* sender = static_cast<QTcpSocket*>(QObject::sender());
}
}
void mynet::on6PackConnection()
{
QTcpSocket *clientSocket = SixPackServer->nextPendingConnection();
connect(clientSocket, SIGNAL(readyRead()), this, SLOT(on6PackReadyRead()));
connect(clientSocket, SIGNAL(stateChanged(QAbstractSocket::SocketState)), this, SLOT(on6PackSocketStateChanged(QAbstractSocket::SocketState)));
Debugprintf("6Pack Connect Sock %x", clientSocket);
}
void mynet::onKISSConnection() void mynet::onKISSConnection()
{ {
@ -186,6 +273,183 @@ void mynet::onKISSConnection()
Debugprintf("KISS Connect Sock %x", clientSocket); Debugprintf("KISS Connect Sock %x", clientSocket);
} }
void Mgmt_del_socket(void * socket)
{
int i;
TMgmtMode * MGMT = NULL;
if (MgmtConCount == 0)
return;
for (i = 0; i < MgmtConCount; i++)
{
if (MgmtConnections[i]->Socket == socket)
{
MGMT = MgmtConnections[i];
break;
}
}
if (MGMT == NULL)
return;
// Need to remove entry and move others down
MgmtConCount--;
while (i < MgmtConCount)
{
MgmtConnections[i] = MgmtConnections[i + 1];
i++;
}
}
void mynet::onMgmtConnection()
{
QTcpSocket *clientSocket = (QTcpSocket *)_MgmtServer->nextPendingConnection();
connect(clientSocket, SIGNAL(readyRead()), this, SLOT(onMgmtReadyRead()));
connect(clientSocket, SIGNAL(stateChanged(QAbstractSocket::SocketState)), this, SLOT(onMgmtSocketStateChanged(QAbstractSocket::SocketState)));
_MgmtSockets.append(clientSocket);
// Create a data structure to hold session info
TMgmtMode * MGMT;
MgmtConnections = (TMgmtMode **)realloc(MgmtConnections, (MgmtConCount + 1) * sizeof(void *));
MGMT = MgmtConnections[MgmtConCount++] = (TMgmtMode *)malloc(sizeof(*MGMT));
memset(MGMT, 0, sizeof(*MGMT));
MGMT->Socket = clientSocket;
Debugprintf("Mgmt Connect Sock %x", clientSocket);
clientSocket->write("Connected to QtSM\r");
}
void mynet::onMgmtSocketStateChanged(QAbstractSocket::SocketState socketState)
{
if (socketState == QAbstractSocket::UnconnectedState)
{
QTcpSocket* sender = static_cast<QTcpSocket*>(QObject::sender());
Mgmt_del_socket(sender);
// free(sender->Msg);
_MgmtSockets.removeOne(sender);
Debugprintf("Mgmt Disconnect Sock %x", sender);
}
}
void mynet::onMgmtReadyRead()
{
QTcpSocket* sender = static_cast<QTcpSocket*>(QObject::sender());
MgmtProcessLine(sender);
}
extern "C" void SendMgmtPTT(int snd_ch, int PTTState)
{
// Won't work in non=gui mode
emit m1.mgmtSetPTT(snd_ch, PTTState);
}
extern "C" char * strlop(char * buf, char delim);
extern "C" char modes_name[modes_count][21];
extern "C" int speed[5];
#ifndef WIN32
extern "C" int memicmp(char *a, char *b, int n);
#endif
void mynet::MgmtProcessLine(QTcpSocket* socket)
{
// Find Session
TMgmtMode * MGMT = NULL;
for (int i = 0; i < MgmtConCount; i++)
{
if (MgmtConnections[i]->Socket == socket)
{
MGMT = MgmtConnections[i];
break;
}
}
if (MGMT == NULL)
{
socket->readAll();
return;
}
while (socket->bytesAvailable())
{
QByteArray datas = socket->peek(512);
char * Line = datas.data();
if (strchr(Line, '\r') == 0)
return;
char * rest = strlop(Line, '\r');
int used = rest - Line;
// Read the upto the cr Null
datas = socket->read(used);
Line = datas.data();
rest = strlop(Line, '\r');
if (memicmp(Line, "QtSMPort ", 8) == 0)
{
if (strlen(Line) > 10)
{
int port = atoi(&Line[8]);
int bpqport = atoi(&Line[10]);
if ((port > 0 && port < 5) && (bpqport > 0 && bpqport < 64))
{
MGMT->BPQPort[port - 1] = bpqport;
socket->write("Ok\r");
}
}
}
else if (memicmp(Line, "Modem ", 6) == 0)
{
int port = atoi(&Line[6]);
if (port > 0 && port < 5)
{
// if any more params - if a name follows, set it else return it
char reply[80];
sprintf(reply, "Port %d Chan %d Freq %d Modem %s \r", MGMT->BPQPort[port - 1], port, rx_freq[port - 1], modes_name[speed[port - 1]]);
socket->write(reply);
}
else
socket->write("Invalid Port\r");
}
else
{
socket->write("Invalid command\r");
}
}
}
void mynet::onKISSSocketStateChanged(QAbstractSocket::SocketState socketState) void mynet::onKISSSocketStateChanged(QAbstractSocket::SocketState socketState)
{ {
if (socketState == QAbstractSocket::UnconnectedState) if (socketState == QAbstractSocket::UnconnectedState)
@ -195,6 +459,7 @@ void mynet::onKISSSocketStateChanged(QAbstractSocket::SocketState socketState)
KISS_del_socket(sender); KISS_del_socket(sender);
_KISSSockets.removeOne(sender); _KISSSockets.removeOne(sender);
Debugprintf("KISS Disconnect Sock %x", sender);
} }
} }
@ -235,7 +500,7 @@ void mynet::sendtoKISS(void * sock, unsigned char * Msg, int Len)
QTcpSocket* socket = (QTcpSocket*)sock; QTcpSocket* socket = (QTcpSocket*)sock;
socket->write((char *)Msg, Len); socket->write((char *)Msg, Len);
} }
// free(Msg); free(Msg);
} }
@ -514,6 +779,36 @@ void mynet::doHLSetPTT(int c)
} }
void mynet::domgmtSetPTT(int snd_ch, int PTTState)
{
char Msg[64];
uint64_t ret;
for (QTcpSocket* socket : _MgmtSockets)
{
// Find Session
TMgmtMode * MGMT = NULL;
for (int i = 0; i < MgmtConCount; i++)
{
if (MgmtConnections[i]->Socket == socket)
{
MGMT = MgmtConnections[i];
break;
}
}
if (MGMT == NULL)
continue;
if (MGMT->BPQPort[snd_ch])
{
sprintf(Msg, "PTT %d %s\r", MGMT->BPQPort[snd_ch], PTTState ? "ON" : "OFF");
ret = socket->write(Msg);
}
}
}

View File

@ -4,6 +4,16 @@
#define CONNECT(sndr, sig, rcvr, slt) connect(sndr, SIGNAL(sig), rcvr, SLOT(slt)) #define CONNECT(sndr, sig, rcvr, slt) connect(sndr, SIGNAL(sig), rcvr, SLOT(slt))
//class myTcpSocket : public QTcpSocket
//{
//public:
// char Msg[512]; // Received message
// int Len;
// int BPQPort[4]; // BPQ port for each modem
//};
class mynet : public QObject class mynet : public QObject
{ {
Q_OBJECT Q_OBJECT
@ -12,6 +22,7 @@ signals:
void HLSetPTT(int c); void HLSetPTT(int c);
void FLRigSetPTT(int c); void FLRigSetPTT(int c);
void mgmtSetPTT(int port, int state);
void startTimer(int Time); void startTimer(int Time);
void stopTimer(); void stopTimer();
@ -23,11 +34,17 @@ public:
public slots: public slots:
void onAGWReadyRead(); void onAGWReadyRead();
void onKISSSocketStateChanged(QAbstractSocket::SocketState socketState); void onKISSSocketStateChanged(QAbstractSocket::SocketState socketState);
void onMgmtSocketStateChanged(QAbstractSocket::SocketState socketState);
void onMgmtReadyRead();
void onKISSReadyRead(); void onKISSReadyRead();
void onAGWSocketStateChanged(QAbstractSocket::SocketState socketState); void onAGWSocketStateChanged(QAbstractSocket::SocketState socketState);
void onKISSConnection(); void onKISSConnection();
void onMgmtConnection();
void MyTimerSlot(); void MyTimerSlot();
void onAGWConnection(); void onAGWConnection();
void on6PackConnection();
void on6PackReadyRead();
void on6PackSocketStateChanged(QAbstractSocket::SocketState socketState);
void dropPTT(); void dropPTT();
void displayError(QAbstractSocket::SocketError socketError); void displayError(QAbstractSocket::SocketError socketError);
@ -45,6 +62,7 @@ public slots:
void dostartTimer(int Time); void dostartTimer(int Time);
void dostopTimer(); void dostopTimer();
void doHLSetPTT(int c); void doHLSetPTT(int c);
void domgmtSetPTT(int chan, int state);
void doFLRigSetPTT(int c); void doFLRigSetPTT(int c);
void readPendingDatagrams(); void readPendingDatagrams();
@ -59,6 +77,7 @@ private:
int bytesReceived; int bytesReceived;
int TotalBytes; int TotalBytes;
int PayloadSize; int PayloadSize;
void MgmtProcessLine(QTcpSocket* socket);
}; };
@ -86,4 +105,3 @@ public: