Merge branch 'develop' into feat-fst280

This commit is contained in:
Bill Somerville 2020-09-11 20:06:20 +01:00
commit 5fdcd8c15a
No known key found for this signature in database
GPG Key ID: D864B06D1E81618F
35 changed files with 9202 additions and 8788 deletions

5
Audio/Audio.pri Normal file
View File

@ -0,0 +1,5 @@
SOURCES += Audio/AudioDevice.cpp Audio/BWFFile.cpp Audio/soundin.cpp \
Audio/soundout.cpp
HEADERS += Audio/AudioDevice.hpp Audio/BWFFile.hpp Audio/soundin.h \
Audio/soundout.h

View File

@ -34,6 +34,12 @@
#
# $Id: FindFFTW3.cmake 15918 2010-06-25 11:12:42Z loose $
# Compatibily with old style MinGW packages with no .dll.a files
# needed since CMake v3.17 because of fix for #20019
if (MINGW)
set (CMAKE_FIND_LIBRARY_SUFFIXES ".dll" ".dll.a" ".a" ".lib")
endif ()
# Use double precision by default.
if (FFTW3_FIND_COMPONENTS MATCHES "^$")
set (_components double)

View File

@ -901,7 +901,7 @@ auto Configuration::special_op_id () const -> SpecialOperatingActivity
void Configuration::set_location (QString const& grid_descriptor)
{
// change the dynamic grid
qDebug () << "Configuration::set_location - location:" << grid_descriptor;
// qDebug () << "Configuration::set_location - location:" << grid_descriptor;
m_->dynamic_grid_ = grid_descriptor.trimmed ();
}
@ -2610,7 +2610,7 @@ void Configuration::impl::transceiver_frequency (Frequency f)
current_offset_ = stations_.offset (f);
cached_rig_state_.frequency (apply_calibration (f + current_offset_));
qDebug () << "Configuration::impl::transceiver_frequency: n:" << transceiver_command_number_ + 1 << "f:" << f;
// qDebug () << "Configuration::impl::transceiver_frequency: n:" << transceiver_command_number_ + 1 << "f:" << f;
Q_EMIT set_transceiver (cached_rig_state_, ++transceiver_command_number_);
}
@ -2636,7 +2636,7 @@ void Configuration::impl::transceiver_tx_frequency (Frequency f)
cached_rig_state_.tx_frequency (apply_calibration (f + current_tx_offset_));
}
qDebug () << "Configuration::impl::transceiver_tx_frequency: n:" << transceiver_command_number_ + 1 << "f:" << f;
// qDebug () << "Configuration::impl::transceiver_tx_frequency: n:" << transceiver_command_number_ + 1 << "f:" << f;
Q_EMIT set_transceiver (cached_rig_state_, ++transceiver_command_number_);
}
}
@ -2645,7 +2645,7 @@ void Configuration::impl::transceiver_mode (MODE m)
{
cached_rig_state_.online (true); // we want the rig online
cached_rig_state_.mode (m);
qDebug () << "Configuration::impl::transceiver_mode: n:" << transceiver_command_number_ + 1 << "m:" << m;
// qDebug () << "Configuration::impl::transceiver_mode: n:" << transceiver_command_number_ + 1 << "m:" << m;
Q_EMIT set_transceiver (cached_rig_state_, ++transceiver_command_number_);
}
@ -2654,7 +2654,7 @@ void Configuration::impl::transceiver_ptt (bool on)
cached_rig_state_.online (true); // we want the rig online
set_cached_mode ();
cached_rig_state_.ptt (on);
qDebug () << "Configuration::impl::transceiver_ptt: n:" << transceiver_command_number_ + 1 << "on:" << on;
// qDebug () << "Configuration::impl::transceiver_ptt: n:" << transceiver_command_number_ + 1 << "on:" << on;
Q_EMIT set_transceiver (cached_rig_state_, ++transceiver_command_number_);
}

View File

@ -577,6 +577,9 @@ quiet period when decoding is done.</string>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="accessibleName">
<string>Serial Port Parameters</string>
</property>
<property name="title">
<string>Serial Port Parameters</string>
</property>
@ -659,6 +662,9 @@ quiet period when decoding is done.</string>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Number of data bits used to communicate with your radio's CAT interface (usually eight).&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="accessibleName">
<string>Data bits</string>
</property>
<property name="title">
<string>Data Bits</string>
</property>
@ -710,6 +716,9 @@ quiet period when decoding is done.</string>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Number of stop bits used when communicating with your radio's CAT interface&lt;/p&gt;&lt;p&gt;(consult you radio's manual for details).&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="accessibleName">
<string>Stop bits</string>
</property>
<property name="title">
<string>Stop Bits</string>
</property>
@ -758,6 +767,9 @@ quiet period when decoding is done.</string>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Flow control protocol used between this computer and your radio's CAT interface (usually &amp;quot;None&amp;quot; but some require &amp;quot;Hardware&amp;quot;).&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="accessibleName">
<string>Handshake</string>
</property>
<property name="title">
<string>Handshake</string>
</property>
@ -824,6 +836,9 @@ a few, particularly some Kenwood rigs, require it).</string>
<property name="toolTip">
<string>Special control of CAT port control lines.</string>
</property>
<property name="accessibleName">
<string>Force Control Lines</string>
</property>
<property name="title">
<string>Force Control Lines</string>
</property>
@ -2346,6 +2361,9 @@ Right click for insert and delete options.</string>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;URL of the ARRL LotW user's last upload dates and times data file which is used to highlight decodes from stations that are known to upload their log file to LotW.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="accessibleName">
<string>URL</string>
</property>
<property name="text">
<string>https://lotw.arrl.org/lotw-user-activity.csv</string>
</property>
@ -2378,6 +2396,9 @@ Right click for insert and delete options.</string>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Adjust this spin box to set the age threshold of LotW user's last upload date that is accepted as a current LotW user.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="accessibleName">
<string>Days since last upload</string>
</property>
<property name="suffix">
<string> days</string>
</property>
@ -2513,6 +2534,9 @@ Right click for insert and delete options.</string>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;FT8 DXpedition mode: Hound operator calling the DX.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="accessibleName">
<string>Hound</string>
</property>
<property name="text">
<string>Hound</string>
</property>
@ -2535,6 +2559,9 @@ Right click for insert and delete options.</string>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;North American VHF/UHF/Microwave contests and others in which a 4-character grid locator is the required exchange.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="accessibleName">
<string>NA VHF Contest</string>
</property>
<property name="text">
<string>NA VHF Contest</string>
</property>
@ -2548,6 +2575,9 @@ Right click for insert and delete options.</string>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;FT8 DXpedition mode: Fox (DXpedition) operator.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="accessibleName">
<string>Fox</string>
</property>
<property name="text">
<string>Fox</string>
</property>
@ -2570,6 +2600,9 @@ Right click for insert and delete options.</string>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;European VHF+ contests requiring a signal report, serial number, and 6-character locator.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="accessibleName">
<string>EU VHF Contest</string>
</property>
<property name="text">
<string>EU VHF Contest</string>
</property>
@ -2598,6 +2631,9 @@ Right click for insert and delete options.</string>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;ARRL RTTY Roundup and similar contests. Exchange is US state, Canadian province, or &amp;quot;DX&amp;quot;.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="accessibleName">
<string>R T T Y Roundup</string>
</property>
<property name="text">
<string>RTTY Roundup messages</string>
</property>
@ -2623,6 +2659,9 @@ Right click for insert and delete options.</string>
<layout class="QFormLayout" name="formLayout_17">
<item row="0" column="0">
<widget class="QLabel" name="labRTTY">
<property name="accessibleName">
<string>RTTY Roundup exchange</string>
</property>
<property name="text">
<string>RTTY RU Exch:</string>
</property>
@ -2661,6 +2700,9 @@ Right click for insert and delete options.</string>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;ARRL Field Day exchange: number of transmitters, Class, and ARRL/RAC section or &amp;quot;DX&amp;quot;.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="accessibleName">
<string>A R R L Field Day</string>
</property>
<property name="text">
<string>ARRL Field Day</string>
</property>
@ -2686,6 +2728,9 @@ Right click for insert and delete options.</string>
<layout class="QFormLayout" name="formLayout_16">
<item row="0" column="0">
<widget class="QLabel" name="labFD">
<property name="accessibleName">
<string>Field Day exchange</string>
</property>
<property name="text">
<string>FD Exch:</string>
</property>
@ -2728,6 +2773,9 @@ Right click for insert and delete options.</string>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;World-Wide Digi-mode contest&lt;/p&gt;&lt;p&gt;&lt;br/&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="accessibleName">
<string>WW Digital Contest</string>
</property>
<property name="text">
<string>WW Digi Contest</string>
</property>
@ -2840,6 +2888,9 @@ Right click for insert and delete options.</string>
<height>50</height>
</size>
</property>
<property name="accessibleName">
<string>Tone spacing</string>
</property>
<property name="title">
<string>Tone spacing</string>
</property>
@ -2878,6 +2929,9 @@ Right click for insert and delete options.</string>
<height>50</height>
</size>
</property>
<property name="accessibleName">
<string>Waterfall spectra</string>
</property>
<property name="title">
<string>Waterfall spectra</string>
</property>
@ -3133,13 +3187,13 @@ Right click for insert and delete options.</string>
</connection>
</connections>
<buttongroups>
<buttongroup name="PTT_method_button_group"/>
<buttongroup name="CAT_stop_bits_button_group"/>
<buttongroup name="CAT_handshake_button_group"/>
<buttongroup name="split_mode_button_group"/>
<buttongroup name="TX_mode_button_group"/>
<buttongroup name="TX_audio_source_button_group"/>
<buttongroup name="special_op_activity_button_group"/>
<buttongroup name="TX_mode_button_group"/>
<buttongroup name="CAT_stop_bits_button_group"/>
<buttongroup name="PTT_method_button_group"/>
<buttongroup name="split_mode_button_group"/>
<buttongroup name="TX_audio_source_button_group"/>
<buttongroup name="CAT_data_bits_button_group"/>
<buttongroup name="CAT_handshake_button_group"/>
</buttongroups>
</ui>

View File

@ -190,7 +190,13 @@ void MessageClient::impl::parse_message (QByteArray const& msg)
quint8 modifiers {0};
in >> time >> snr >> delta_time >> delta_frequency >> mode >> message
>> low_confidence >> modifiers;
TRACE_UDP ("Reply: time:" << time << "snr:" << snr << "dt:" << delta_time << "df:" << delta_frequency << "mode:" << mode << "message:" << message << "low confidence:" << low_confidence << "modifiers: 0x" << hex << modifiers);
TRACE_UDP ("Reply: time:" << time << "snr:" << snr << "dt:" << delta_time << "df:" << delta_frequency << "mode:" << mode << "message:" << message << "low confidence:" << low_confidence << "modifiers: 0x"
#if QT_VERSION >= QT_VERSION_CHECK (5, 15, 0)
<< Qt::hex
#else
<< hex
#endif
<< modifiers);
if (check_status (in) != Fail)
{
Q_EMIT self_->reply (time, snr, delta_time, delta_frequency

View File

@ -21,7 +21,6 @@
#if QT_VERSION >= QT_VERSION_CHECK(5, 15, 0)
#include <QRandomGenerator>
#endif
#include <QDebug>
#include "Configuration.hpp"
#include "pimpl_impl.hpp"
@ -95,11 +94,11 @@ public:
// handle re-opening asynchronously
auto connection = QSharedPointer<QMetaObject::Connection>::create ();
*connection = connect (socket_.data (), &QAbstractSocket::disconnected, [this, connection] () {
qDebug () << "PSKReporter::impl::check_connection: disconnected, socket state:" << socket_->state ();
disconnect (*connection);
check_connection ();
});
// close gracefully
send_report (true);
socket_->close ();
}
else
@ -122,7 +121,6 @@ public:
default:
spots_.clear ();
qDebug () << "PSKReporter::impl::handle_socket_error:" << socket_->errorString ();
Q_EMIT self_->errorOccurred (socket_->errorString ());
break;
}
@ -268,7 +266,6 @@ void PSKReporter::impl::build_preamble (QDataStream& message)
<< ++sequence_number_ // Sequence Number
<< observation_id_; // Observation Domain ID
// qDebug () << "PSKReporter::impl::build_preamble: send_descriptors_:" << send_descriptors_;
if (send_descriptors_)
{
--send_descriptors_;
@ -333,7 +330,6 @@ void PSKReporter::impl::build_preamble (QDataStream& message)
}
}
// qDebug () << "PSKReporter::impl::build_preamble: send_receiver_data_:" << send_receiver_data_;
// if (send_receiver_data_)
{
// --send_receiver_data_;
@ -361,8 +357,6 @@ void PSKReporter::impl::build_preamble (QDataStream& message)
void PSKReporter::impl::send_report (bool send_residue)
{
check_connection ();
// qDebug () << "PSKReporter::impl::send_report: send_residue:" << send_residue;
if (QAbstractSocket::ConnectedState != socket_->state ()) return;
QDataStream message {&payload_, QIODevice::WriteOnly | QIODevice::Append};
@ -370,13 +364,11 @@ void PSKReporter::impl::send_report (bool send_residue)
if (!payload_.size ())
{
// qDebug () << "PSKReporter::impl::send_report: building header";
// Build header, optional descriptors, and receiver information
build_preamble (message);
}
auto flush = flushing () || send_residue;
// qDebug () << "PSKReporter::impl::send_report: flush:" << flush;
while (spots_.size () || flush)
{
if (!payload_.size ())
@ -391,7 +383,6 @@ void PSKReporter::impl::send_report (bool send_residue)
tx_out
<< quint16 (0x50e3) // Template ID
<< quint16 (0u); // Length (place-holder)
// qDebug () << "PSKReporter::impl::send_report: set data set header";
}
// insert any residue
@ -399,7 +390,6 @@ void PSKReporter::impl::send_report (bool send_residue)
{
tx_out.writeRawData (tx_residue_.constData (), tx_residue_.size ());
tx_residue_.clear ();
// qDebug () << "PSKReporter::impl::send_report: inserted data residue";
}
while (spots_.size () || flush)
@ -408,7 +398,6 @@ void PSKReporter::impl::send_report (bool send_residue)
if (spots_.size ())
{
auto const& spot = spots_.dequeue ();
// qDebug () << "PSKReporter::impl::send_report: processing spotted call:" << spot.call_;
// Sender information
writeUtfString (tx_out, spot.call_);
@ -440,7 +429,6 @@ void PSKReporter::impl::send_report (bool send_residue)
if (len <= MAX_PAYLOAD_LENGTH)
{
tx_data_size = tx_data_.size ();
// qDebug () << "PSKReporter::impl::send_report: sending short payload:" << tx_data_size;
}
QByteArray tx {tx_data_.left (tx_data_size)};
QDataStream out {&tx, QIODevice::WriteOnly | QIODevice::Append};
@ -462,7 +450,6 @@ void PSKReporter::impl::send_report (bool send_residue)
// Send data to PSK Reporter site
socket_->write (payload_); // TODO: handle errors
// qDebug () << "PSKReporter::impl::send_report: sent payload:" << payload_.size () << "observation id:" << observation_id_;
flush = false; // break loop
message.device ()->seek (0u);
payload_.clear (); // Fresh message
@ -470,7 +457,6 @@ void PSKReporter::impl::send_report (bool send_residue)
tx_residue_ = tx_data_.right (tx_data_.size () - tx_data_size);
tx_out.device ()->seek (0u);
tx_data_.clear ();
// qDebug () << "PSKReporter::impl::send_report: payload sent residue length:" << tx_residue_.size ();
break;
}
}
@ -523,6 +509,7 @@ bool PSKReporter::addRemoteStation (QString const& call, QString const& grid, Ra
void PSKReporter::sendReport (bool last)
{
m_->check_connection ();
if (m_->socket_ && QAbstractSocket::ConnectedState == m_->socket_->state ())
{
m_->send_report (true);

View File

@ -13,6 +13,19 @@
Copyright 2001 - 2020 by Joe Taylor, K1JT.
Release: WSJT-X 2.3.0-rc1
Sept DD, 2020
-------------------------
WSJT-X 2.3.0-rc1 is a beta-quality release candidate for a program
upgrade that provides a number of new features and capabilities.
These include:
- The *On Dx Echo* Doppler compensation method has been modified in
response to feedback from Users. Basic functionality is unchanged.
See the User Guide (Section 8.1) for more information.
Release: WSJT-X 2.2.2
June 22, 2020
---------------------

View File

@ -15,6 +15,7 @@ QRA66 1111110101101101000100000011000000
ISCAT 1001110000000001100000000000000000
MSK144 1011111101000000000100010000000000
WSPR 0000000000000000010100000000000000
FST4 1111110001001110000100000001000000
FST4W 0000000000000000010100000000000001
Echo 0000000000000000000000100000000000
FCal 0011010000000000000000000000010000

View File

@ -40,7 +40,6 @@ sudo dpkg -P wsjtx
You may also need to execute the following command in a terminal:
[example]
....
sudo apt install libgfortran5 libqt5widgets5 libqt5network5 \
libqt5printsupport5 libqt5multimedia5-plugins libqt5serialport5 \
@ -73,7 +72,6 @@ sudo rpm -e wsjtx
You may also need to execute the following command in a terminal:
[example]
....
sudo dnf install libgfortran fftw-libs-single qt5-qtbase \
qt5-qtmultimedia qt5-qtserialport qt5-qtsvg \

View File

@ -21,18 +21,30 @@ TIP: Your computer may be configured so that this directory is
`"%LocalAppData%\WSJT-X\"`.
* The built-in Windows facility for time synchronization is usually
not adequate. We recommend the program _Meinberg NTP_ (see
{ntpsetup} for downloading and installation instructions) or
_Dimension 4_ from {dimension4}. Recent versions of Windows 10 are
now shipped with a more capable Internet time synchronization
service that is suitable if configured appropriately.
not adequate. We recommend the program _Meinberg NTP Client_ (see
{ntpsetup} for downloading and installation instructions). Recent
versions of Windows 10 are now shipped with a more capable Internet
time synchronization service that is suitable if configured
appropriately. We do not recommend SNTP time setting tools or others
that make periodic correction steps, _WSJT-X_ requires that the PC
clock be monotonic.
NOTE: Having a PC clock that appears to be synchronized to UTC is not
sufficient, monotonicity means that the clock must not be
stepped backwards or forwards during corrections, instead the
clock frequency must be adjusted to correct synchronization
errors gradually.
[[OPENSSL]]
image:LoTW_TLS_error.png[_WSJT-X_ LoTW download TLS error,
align="center"]
* _WSJT-X_ requires installation of the _OpenSSL_ libraries. Suitable libraries may already be installed on your system. If they are not, you will see this error shortly after requesting a fetch of the latest LoTW users database. To fix this, install the _OpenSSL_ libraries.
* _WSJT-X_ requires installation of the _OpenSSL_ libraries. Suitable
libraries may already be installed on your system. If they are not,
you will see this error shortly after requesting a fetch of the
latest LoTW users database. To fix this, install the _OpenSSL_
libraries.
** You can download a suitable _OpenSSL_ package for Windows from
{win_openssl_packages}; you need the latest *Windows Light*

View File

@ -92,16 +92,14 @@ thing, both stations will have the required Doppler compensation.
Moreover, anyone else using this option will hear both of you
without the need for manual frequency changes.
- Select *On Dx Echo* when your QSO partner is not using automated
Doppler tracking, and announces his/her transmit frequency and listening
on their own echo frequency. When clicked, this Doppler method will
set your rig frequency on receive to correct for the mutual Doppler
shift. On transmit, your rig frequency will be set so that your
QSO partner will receive you on the same frequency as their own echo
at the start of the QSO. As the QSO proceeds, your QSO partner will
receive you on this starting frequency so that they do not have to
retune their receiver as the Doppler changes. Sked frequency in this
case is set to that announced by your QSO partner.
- Select *On Dx Echo* when your QSO partner announces his/her transmit
frequency and that they are listening on their own echo
frequency. When clicked, this Doppler method will set your rig
frequency on receive to correct for the mutual Doppler shift. On
transmit, your rig frequency will be set so that your QSO partner will
receive you on the same frequency as they receive their own echo.
Sked frequency in this case is set to that announced by your QSO
partner.
- Select *Call DX* after tuning the radio manually to find a station,
with the Doppler mode initially set to *None*. You may be tuning the band

View File

@ -208,11 +208,12 @@ subroutine multimode_decoder(ss,id2,params,nfsample)
! We're in FST4 mode
ndepth=iand(params%ndepth,3)
iwspr=0
params%nsubmode=0
call timer('dec240 ',0)
call my_fst4%decode(fst4_decoded,id2,params%nutc, &
params%nQSOProgress,params%nfqso,params%nfa,params%nfb, &
params%nsubmode,ndepth,params%ntr,params%nexp_decode, &
params%ntol,params%emedelay, &
call my_fst4%decode(fst4_decoded,id2,params%nutc, &
params%nQSOProgress,params%nfa,params%nfb, &
params%nfqso,ndepth,params%ntr, &
params%nexp_decode,params%ntol,params%emedelay, &
logical(params%lapcqonly),mycall,hiscall,iwspr)
call timer('dec240 ',1)
go to 800
@ -224,9 +225,9 @@ subroutine multimode_decoder(ss,id2,params,nfsample)
iwspr=1
call timer('dec240 ',0)
call my_fst4%decode(fst4_decoded,id2,params%nutc, &
params%nQSOProgress,params%nfqso,params%nfa,params%nfb, &
params%nsubmode,ndepth,params%ntr,params%nexp_decode, &
params%ntol,params%emedelay, &
params%nQSOProgress,params%nfa,params%nfb, &
params%nfqso,ndepth,params%ntr, &
params%nexp_decode,params%ntol,params%emedelay, &
logical(params%lapcqonly),mycall,hiscall,iwspr)
call timer('dec240 ',1)
go to 800

View File

@ -29,9 +29,9 @@ module fst4_decode
contains
subroutine decode(this,callback,iwave,nutc,nQSOProgress,nfqso, &
nfa,nfb,nsubmode,ndepth,ntrperiod,nexp_decode,ntol, &
emedelay,lapcqonly,mycall,hiscall,iwspr)
subroutine decode(this,callback,iwave,nutc,nQSOProgress,nfa,nfb,nfqso, &
ndepth,ntrperiod,nexp_decode,ntol,emedelay,lapcqonly,mycall, &
hiscall,iwspr)
use timer_module, only: timer
use packjt77
@ -64,7 +64,7 @@ contains
integer naptypes(0:5,4) ! (nQSOProgress,decoding pass)
integer mcq(29),mrrr(19),m73(19),mrr73(19)
logical badsync,unpk77_success,single_decode
logical badsync,unpk77_success
logical first,nohiscall,lwspr,ex
integer*2 iwave(30*60*12000)
@ -76,16 +76,13 @@ contains
data rvec/0,1,0,0,1,0,1,0,0,1,0,1,1,1,1,0,1,0,0,0,1,0,0,1,1,0,1,1,0, &
1,0,0,1,0,1,1,0,0,0,0,1,0,0,0,1,0,1,0,0,1,1,1,1,0,0,1,0,1, &
0,1,0,1,0,1,1,0,1,1,1,1,1,0,0,0,1,0,1/
data first/.true./
data first/.true./,hmod/1/
save first,apbits,nappasses,naptypes,mycall0,hiscall0
this%callback => callback
dxcall13=hiscall ! initialize for use in packjt77
mycall13=mycall
fMHz=1.0
if(iwspr.ne.0.and.iwspr.ne.1) return
if(first) then
@ -157,57 +154,43 @@ contains
endif
!************************************
hmod=2**nsubmode
if(nfqso+nqsoprogress.eq.-999) return
Keff=91
nmax=15*12000
single_decode=iand(nexp_decode,32).eq.32
if(ntrperiod.eq.15) then
nsps=720
nmax=15*12000
ndown=18/hmod !nss=40,80,160,400
if(hmod.eq.4) ndown=4
if(hmod.eq.8) ndown=2
ndown=18 !nss=40,80,160,400
nfft1=int(nmax/ndown)*ndown
else if(ntrperiod.eq.30) then
nsps=1680
nmax=30*12000
ndown=42/hmod !nss=40,80,168,336
ndown=42 !nss=40,80,168,336
nfft1=359856 !nfft2=8568=2^3*3^2*7*17
if(hmod.eq.4) then
ndown=10
nfft1=nmax
endif
if(hmod.eq.8) then
ndown=5
nfft1=nmax
endif
else if(ntrperiod.eq.60) then
nsps=3888
nmax=60*12000
ndown=96/hmod !nss=36,81,162,324
if(hmod.eq.1) ndown=108
ndown=108
nfft1=7500*96 ! nfft2=7500=2^2*3*5^4
else if(ntrperiod.eq.120) then
nsps=8200
nmax=120*12000
ndown=200/hmod !nss=40,82,164,328
if(hmod.eq.1) ndown=205
ndown=205 !nss=40,82,164,328
nfft1=7200*200 ! nfft2=7200=2^5*3^2*5^2
else if(ntrperiod.eq.300) then
nsps=21504
nmax=300*12000
ndown=512/hmod !nss=42,84,168,336
ndown=512 !nss=42,84,168,336
nfft1=7020*512 ! nfft2=7020=2^2*3^3*5*13
else if(ntrperiod.eq.900) then
nsps=66560
nmax=900*12000
ndown=1664/hmod !nss=40,80,160,320
ndown=1664 !nss=40,80,160,320
nfft1=6480*1664 ! nfft2=6480=2^4*3^4*5
else if(ntrperiod.eq.1800) then
nsps=134400
nmax=1800*12000
ndown=3360/hmod !nss=40,80,160,320
ndown=3360 !nss=40,80,160,320
nfft1=6426*3360 ! nfft2=6426=2*3^3*7*17
end if
nss=nsps/ndown
@ -218,7 +201,7 @@ contains
dt2=1.0/fs2
tt=nsps*dt !Duration of "itone" symbols (s)
baud=1.0/tt
sigbw=4.0*hmod*baud
sigbw=4.0*baud
nfft2=nfft1/ndown !make sure that nfft1 is exactly nfft2*ndown
nfft1=nfft2*ndown
nh1=nfft1/2
@ -227,13 +210,13 @@ contains
allocate( c2(0:nfft2-1) )
allocate( cframe(0:160*nss-1) )
jittermax=2
if(ndepth.eq.3) then
nblock=4
jittermax=2
norder=3
elseif(ndepth.eq.2) then
nblock=1
if(hmod.eq.1) nblock=3
nblock=3
jittermax=0
norder=3
elseif(ndepth.eq.1) then
@ -249,22 +232,16 @@ contains
! The big fft is done once and is used for calculating the smoothed spectrum
! and also for downconverting/downsampling each candidate.
call four2a(c_bigfft,nfft1,1,-1,0) !r2c
! call blank2(nfa,nfb,nfft1,c_bigfft,iwave)
nhicoh=1
nsyncoh=8
if(iwspr.eq.1) then
fa=1400.0
fb=1600.0
else
fa=max(100,nint(nfqso+1.5*hmod*baud-ntol))
fb=min(4800,nint(nfqso+1.5*hmod*baud+ntol))
endif
fa=max(100,nint(nfqso+1.5*baud-ntol))
fb=min(4800,nint(nfqso+1.5*baud+ntol))
minsync=1.20
if(ntrperiod.eq.15) minsync=1.15
! Get first approximation of candidate frequencies
call get_candidates_fst4(c_bigfft,nfft1,nsps,hmod,fs,fa,fb, &
call get_candidates_fst4(c_bigfft,nfft1,nsps,hmod,fs,fa,fb,nfa,nfb, &
minsync,ncand,candidates)
ndecodes=0
@ -485,7 +462,7 @@ contains
endif
nsnr=nint(xsnr)
qual=0.
fsig=fc_synced - 1.5*hmod*baud
fsig=fc_synced - 1.5*baud
if(ex) then
write(21,3021) nutc,icand,itry,nsyncoh,iaptype, &
ijitter,ntype,nsync_qual,nharderrors,dmin, &
@ -649,7 +626,7 @@ contains
end subroutine fst4_downsample
subroutine get_candidates_fst4(c_bigfft,nfft1,nsps,hmod,fs,fa,fb, &
subroutine get_candidates_fst4(c_bigfft,nfft1,nsps,hmod,fs,fa,fb,nfa,nfb, &
minsync,ncand,candidates)
complex c_bigfft(0:nfft1/2) !Full length FFT of raw data
@ -671,20 +648,10 @@ contains
ndh=nd/2
ia=nint(max(100.0,fa)/df2) !Low frequency search limit
ib=nint(min(4800.0,fb)/df2) !High frequency limit
signal_bw=4*(12000.0/nsps)*hmod
analysis_bw=min(4800.0,fb)-max(100.0,fa)
xnoise_bw=10.0*signal_bw !Is this a good compromise?
if(xnoise_bw .lt. 400.0) xnoise_bw=400.0
if(analysis_bw.gt.xnoise_bw) then !Estimate noise baseline over analysis bw
ina=0.9*ia
inb=min(int(1.1*ib),nfft1/2)
else !Estimate noise baseline over noise bw
fcenter=(fa+fb)/2.0
fl = max(100.0,fcenter-xnoise_bw/2.)/df2
fh = min(4800.0,fcenter+xnoise_bw/2.)/df2
ina=nint(fl)
inb=nint(fh)
endif
ina=nint(max(100.0,real(nfa))/df2) !Low freq limit for noise baseline fit
inb=nint(min(4800.0,real(nfb))/df2) !High freq limit for noise fit
if(ia.lt.ina) ia=ina
if(ib.gt.inb) ib=inb
nnw=nint(48000.*nsps*2./fs)
allocate (s(nnw))
s=0. !Compute low-resolution power spectrum
@ -791,7 +758,6 @@ contains
complex, allocatable :: cwave(:) !Reconstructed complex signal
complex, allocatable :: g(:) !Channel gain, g(t) in QEX paper
real,allocatable :: ss(:) !Computed power spectrum of g(t)
real,allocatable,save :: ssavg(:) !Computed power spectrum of g(t)
integer itone(160) !Tones for this message
integer*2 iwave(nmax) !Raw Rx data
integer hmod !Modulation index

View File

@ -8,6 +8,7 @@
#include <boost/multi_index/ordered_index.hpp>
#include <boost/multi_index/key_extractors.hpp>
#include <boost/range/iterator_range.hpp>
#include <QCoreApplication>
#include <QtConcurrent/QtConcurrentRun>
#include <QFuture>
#include <QFutureWatcher>
@ -19,7 +20,9 @@
#include <QFileInfo>
#include <QFile>
#include <QTextStream>
#include <QDateTime>
#include "Configuration.hpp"
#include "revision_utils.hpp"
#include "qt_helpers.hpp"
#include "pimpl_impl.hpp"
@ -252,7 +255,7 @@ namespace
}
else
{
throw LoaderException (std::runtime_error {"Invalid ADIF field " + fieldName.toStdString () + ": " + record.toStdString ()});
throw LoaderException (std::runtime_error {QCoreApplication::translate ("WorkedBefore", "Invalid ADIF field %0: %1").arg (fieldName).arg (record).toLocal8Bit ()});
}
if (closingBracketIndex > fieldNameIndex && fieldLengthIndex > fieldNameIndex && fieldLengthIndex < closingBracketIndex)
@ -269,7 +272,7 @@ namespace
}
else
{
throw LoaderException (std::runtime_error {"Malformed ADIF field " + fieldName.toStdString () + ": " + record.toStdString ()});
throw LoaderException (std::runtime_error {QCoreApplication::translate ("WorkedBefore", "Malformed ADIF field %0: %1").arg (fieldName).arg (record).toLocal8Bit ()});
}
}
return QString {};
@ -306,7 +309,7 @@ namespace
{
if (end_position < 0)
{
throw LoaderException (std::runtime_error {"Invalid ADIF header"});
throw LoaderException (std::runtime_error {QCoreApplication::translate ("WorkedBefore", "Invalid ADIF header").toLocal8Bit ()});
}
buffer.remove (0, end_position + 5);
}
@ -352,7 +355,7 @@ namespace
}
else
{
throw LoaderException (std::runtime_error {"Error opening ADIF log file for read: " + inputFile.errorString ().toStdString ()});
throw LoaderException (std::runtime_error {QCoreApplication::translate ("WorkedBefore", "Error opening ADIF log file for read: %0").arg (inputFile.errorString ()).toLocal8Bit ()});
}
}
return worked;
@ -442,7 +445,18 @@ bool WorkedBefore::add (QString const& call
QTextStream out {&file};
if (!file.size ())
{
out << "WSJT-X ADIF Export<eoh>" << // new file
auto ts = QDateTime::currentDateTimeUtc ().toString ("yyyyMMdd HHmmss");
auto ver = version (true);
out << // new file
QString {
"ADIF Export\n"
"<adif_ver:5>3.1.1\n"
"<created_timestamp:15>%0\n"
"<programid:6>WSJT-X\n"
"<programversion:%1>%2\n"
"<eoh>"
}.arg (ts).arg (ver.size ()).arg (ver)
<<
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
endl
#else

View File

@ -79,7 +79,7 @@ QByteArray LogBook::QSOToADIF (QString const& hisCall, QString const& hisGrid, Q
QString t;
t = "<call:" + QString::number(hisCall.size()) + ">" + hisCall;
t += " <gridsquare:" + QString::number(hisGrid.size()) + ">" + hisGrid;
if (mode != "FT4")
if (mode != "FT4" && mode != "FST4")
{
t += " <mode:" + QString::number(mode.size()) + ">" + mode;
}

View File

@ -28,7 +28,9 @@ namespace
{"15m", 21000000u, 21450000u},
{"12m", 24890000u, 24990000u},
{"10m", 28000000u, 29700000u},
{"8m", 40000000u, 45000000u},
{"6m", 50000000u, 54000000u},
{"5m", 54000001u, 69900000u},
{"4m", 70000000u, 71000000u},
{"2m", 144000000u, 148000000u},
{"1.25m", 222000000u, 225000000u},

View File

@ -46,16 +46,14 @@ namespace
{20000000, Modes::FreqCal, IARURegions::ALL},
{136000, Modes::WSPR, IARURegions::ALL},
{136200, Modes::FST4W, IARURegions::ALL},
{136130, Modes::JT65, IARURegions::ALL},
{136000, Modes::FST4, IARURegions::ALL},
{136000, Modes::FST4W, IARURegions::ALL},
{136130, Modes::JT9, IARURegions::ALL},
{136130, Modes::FST4, IARURegions::ALL},
{474200, Modes::JT65, IARURegions::ALL},
{474200, Modes::JT9, IARURegions::ALL},
{474200, Modes::FST4, IARURegions::ALL},
{474200, Modes::WSPR, IARURegions::ALL},
{474400, Modes::FST4W, IARURegions::ALL},
{474200, Modes::FST4W, IARURegions::ALL},
{1836600, Modes::WSPR, IARURegions::ALL},
{1836800, Modes::FST4W, IARURegions::ALL},
@ -93,10 +91,8 @@ namespace
//
{3570000, Modes::JT65, IARURegions::ALL}, // JA compatible
{3572000, Modes::JT9, IARURegions::ALL},
{3572000, Modes::FST4, IARURegions::ALL},
{3573000, Modes::FT8, IARURegions::ALL}, // above as below JT65 is out of DM allocation
{3568600, Modes::WSPR, IARURegions::ALL}, // needs guard marker and lock out
{3568800, Modes::FST4W, IARURegions::ALL},
{3575000, Modes::FT4, IARURegions::ALL}, // provisional
{3568000, Modes::FT4, IARURegions::R3}, // provisional
@ -132,11 +128,9 @@ namespace
// 7110 LSB EMCOMM
//
{7038600, Modes::WSPR, IARURegions::ALL},
{7038800, Modes::FST4W, IARURegions::ALL},
{7074000, Modes::FT8, IARURegions::ALL},
{7076000, Modes::JT65, IARURegions::ALL},
{7078000, Modes::JT9, IARURegions::ALL},
{7078000, Modes::FST4, IARURegions::ALL},
{7047500, Modes::FT4, IARURegions::ALL}, // provisional - moved
// up 500Hz to clear
// W1AW code practice QRG
@ -170,9 +164,7 @@ namespace
{10136000, Modes::FT8, IARURegions::ALL},
{10138000, Modes::JT65, IARURegions::ALL},
{10138700, Modes::WSPR, IARURegions::ALL},
{10138900, Modes::FST4W, IARURegions::ALL},
{10140000, Modes::JT9, IARURegions::ALL},
{10140000, Modes::FST4, IARURegions::ALL},
{10140000, Modes::FT4, IARURegions::ALL}, // provisional
// Band plans (all USB dial unless stated otherwise)
@ -213,11 +205,9 @@ namespace
// 14106.5 OLIVIA 1000 (main QRG)
//
{14095600, Modes::WSPR, IARURegions::ALL},
{14095800, Modes::FST4W, IARURegions::ALL},
{14074000, Modes::FT8, IARURegions::ALL},
{14076000, Modes::JT65, IARURegions::ALL},
{14078000, Modes::JT9, IARURegions::ALL},
{14078000, Modes::FST4, IARURegions::ALL},
{14080000, Modes::FT4, IARURegions::ALL}, // provisional
// Band plans (all USB dial unless stated otherwise)
@ -250,33 +240,25 @@ namespace
{18100000, Modes::FT8, IARURegions::ALL},
{18102000, Modes::JT65, IARURegions::ALL},
{18104000, Modes::JT9, IARURegions::ALL},
{18104000, Modes::FST4, IARURegions::ALL},
{18104000, Modes::FT4, IARURegions::ALL}, // provisional
{18104600, Modes::WSPR, IARURegions::ALL},
{18104800, Modes::FST4W, IARURegions::ALL},
{21074000, Modes::FT8, IARURegions::ALL},
{21076000, Modes::JT65, IARURegions::ALL},
{21078000, Modes::JT9, IARURegions::ALL},
{21078000, Modes::FST4, IARURegions::ALL},
{21094600, Modes::WSPR, IARURegions::ALL},
{21094800, Modes::FST4W, IARURegions::ALL},
{21140000, Modes::FT4, IARURegions::ALL},
{24915000, Modes::FT8, IARURegions::ALL},
{24917000, Modes::JT65, IARURegions::ALL},
{24919000, Modes::JT9, IARURegions::ALL},
{24919000, Modes::FST4, IARURegions::ALL},
{24919000, Modes::FT4, IARURegions::ALL}, // provisional
{24924600, Modes::WSPR, IARURegions::ALL},
{24924800, Modes::FST4W, IARURegions::ALL},
{28074000, Modes::FT8, IARURegions::ALL},
{28076000, Modes::JT65, IARURegions::ALL},
{28078000, Modes::JT9, IARURegions::ALL},
{28078000, Modes::FST4, IARURegions::ALL},
{28124600, Modes::WSPR, IARURegions::ALL},
{28124800, Modes::FST4W, IARURegions::ALL},
{28180000, Modes::FT4, IARURegions::ALL},
{50200000, Modes::Echo, IARURegions::ALL},
@ -287,11 +269,8 @@ namespace
{50260000, Modes::MSK144, IARURegions::R3},
{50293000, Modes::WSPR, IARURegions::R2},
{50293000, Modes::WSPR, IARURegions::R3},
{50293200, Modes::FST4W, IARURegions::R2},
{50293200, Modes::FST4W, IARURegions::R3},
{50310000, Modes::JT65, IARURegions::ALL},
{50312000, Modes::JT9, IARURegions::ALL},
{50312000, Modes::FST4, IARURegions::ALL},
{50313000, Modes::FT8, IARURegions::ALL},
{50318000, Modes::FT4, IARURegions::ALL}, // provisional
{50323000, Modes::FT8, IARURegions::ALL},
@ -300,7 +279,6 @@ namespace
{70102000, Modes::JT65, IARURegions::R1},
{70104000, Modes::JT9, IARURegions::R1},
{70091000, Modes::WSPR, IARURegions::R1},
{70091200, Modes::FST4W, IARURegions::R2},
{70230000, Modes::MSK144, IARURegions::R1},
{144120000, Modes::JT65, IARURegions::ALL},
@ -310,7 +288,6 @@ namespace
{144360000, Modes::MSK144, IARURegions::R1},
{144150000, Modes::MSK144, IARURegions::R2},
{144489000, Modes::WSPR, IARURegions::ALL},
{144489200, Modes::FST4W, IARURegions::R2},
{144120000, Modes::QRA64, IARURegions::ALL},
{222065000, Modes::Echo, IARURegions::R2},

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -54,7 +54,7 @@ void LiveFrequencyValidator::fixup (QString& input) const
input = input.toLower ();
QVector<QVariant> frequencies;
for (auto const& item : frequencies_->frequency_list ())
for (auto const& item : *frequencies_)
{
if (bands_->find (item.frequency_) == input)
{

View File

@ -21,9 +21,9 @@ CAboutDlg::CAboutDlg(QWidget *parent) :
"&copy; 2001-2020 by Joe Taylor, K1JT, Bill Somerville, G4WJS, <br />"
"and Steve Franke, K9AN. <br /><br />"
"We gratefully acknowledge contributions from AC6SL, AE4JY,<br />"
"DF2ET, DJ0OT, G3WDG, G4KLA, IV3NWV, IW3RAB, K3WYC, KA6MAL,<br />"
"KA9Q, KB1ZMX, KD6EKQ, KI7MT, KK1D, ND0B, PY2SDR, VE1SKY,<br />"
"VK3ACF, VK4BDJ, VK7MO, W4TI, W4TV, and W9MDB.<br /><br />"
"DF2ET, DJ0OT, G3WDG, G4KLA, IV3NWV, IW3RAB, KA1GT, K3WYC,<br />"
"KA6MAL, KA9Q, KB1ZMX, KD6EKQ, KI7MT, KK1D, ND0B, PY2SDR,<br />"
"VE1SKY, VK3ACF, VK4BDJ, VK7MO, W4TI, W4TV, and W9MDB.<br /><br />"
"WSJT-X is licensed under the terms of Version 3 <br />"
"of the GNU General Public License (GPL) <br /><br />"
"<a href=" WSJTX_STRINGIZE (PROJECT_HOMEPAGE) ">"

View File

@ -42,7 +42,7 @@ Astro::Astro(QSettings * settings, Configuration const * configuration, QWidget
, m_DopplerMethod {0}
, m_dop {0}
, m_dop00 {0}
, m_dx_two_way_dop {0}
//, m_dx_two_way_dop {0}
{
ui_->setupUi (this);
setWindowTitle (QApplication::applicationName () + " - " + tr ("Astronomical Data"));
@ -77,8 +77,8 @@ void Astro::read_settings ()
case 1: ui_->rbFullTrack->setChecked (true); break;
case 2: ui_->rbConstFreqOnMoon->setChecked (true); break;
case 3: ui_->rbOwnEcho->setChecked (true); break;
case 4: ui_->rbOnDxEcho->setChecked (true); break;
case 5: ui_->rbCallDx->setChecked (true); break;
case 4: ui_->rbOnDxEcho->setChecked (true); break;
case 5: ui_->rbCallDx->setChecked (true); break;
}
move (settings_->value ("window/pos", pos ()).toPoint ());
}
@ -168,38 +168,35 @@ auto Astro::astroUpdate(QDateTime const& t, QString const& mygrid, QString const
switch (m_DopplerMethod)
{
case 1: // All Doppler correction done here; DX station stays at nominal dial frequency.
correction.rx = m_dop;
break;
case 4: // All Doppler correction done here; DX station stays at nominal dial frequency. (Trial for OnDxEcho)
correction.rx = m_dop;
break;
//case 5: // All Doppler correction done here; DX station stays at nominal dial frequency.
correction.rx = m_dop;
break;
case 4: // All Doppler correction done here; DX station stays at nominal dial frequency. (Trial for OnDxEcho)
correction.rx = m_dop;
break;
//case 5: // All Doppler correction done here; DX station stays at nominal dial frequency.
case 3: // Both stations do full correction on Rx and none on Tx
//correction.rx = dx_is_self ? m_dop00 : m_dop;
correction.rx = m_dop00; // Now always sets RX to *own* echo freq
correction.rx = m_dop00; // Now always sets RX to *own* echo freq
break;
case 2:
case 2:
// Doppler correction to constant frequency on Moon
correction.rx = m_dop00 / 2;
break;
}
switch (m_DopplerMethod)
{
case 1: correction.tx = -correction.rx;
break;
case 2: correction.tx = -correction.rx;
break;
case 3: correction.tx = 0;
break;
case 4: // correction.tx = m_dop - m_dop00;
correction.tx = m_dx_two_way_dop - m_dop;
qDebug () << "correction.tx:" << correction.tx;
break;
case 5: correction.tx = - m_dop00;
break;
case 1: correction.tx = -correction.rx;
break;
case 2: correction.tx = -correction.rx;
break;
case 3: correction.tx = 0;
break;
case 4: // correction.tx = m_dop - m_dop00;
correction.tx = (2 * (m_dop - (m_dop00/2))) - m_dop;
//qDebug () << "correction.tx:" << correction.tx;
break;
case 5: correction.tx = - m_dop00;
break;
}
//if (3 != m_DopplerMethod || 4 != m_DopplerMethod) correction.tx = -correction.rx;
@ -242,22 +239,20 @@ auto Astro::astroUpdate(QDateTime const& t, QString const& mygrid, QString const
case 2:
// Doppler correction to constant frequency on Moon
offset = m_dop00 / 2;
break;
case 4:
// Doppler correction for OnDxEcho
offset = m_dop - m_dx_two_way_dop;
offset = m_dop00 / 2;
break;
case 4:
// Doppler correction for OnDxEcho
offset = m_dop - (2 * (m_dop - (m_dop00/2)));
break;
//case 5: correction.tx = - m_dop00;
case 5: offset = m_dop00;// version for _7
break;
//case 5: correction.tx = - m_dop00;
case 5: offset = m_dop00;// version for _7
break;
}
correction.tx = -offset;
qDebug () << "correction.tx (no tx qsy):" << correction.tx;
//qDebug () << "correction.tx (no tx qsy):" << correction.tx;
}
}
return correction;
@ -281,14 +276,14 @@ void Astro::on_rbFullTrack_clicked()
Q_EMIT tracking_update ();
}
void Astro::on_rbOnDxEcho_clicked(bool checked)
void Astro::on_rbOnDxEcho_clicked() //on_rbOnDxEcho_clicked(bool checked)
{
m_DopplerMethod = 4;
check_split ();
if (checked) {
m_dx_two_way_dop = 2 * (m_dop - (m_dop00/2));
qDebug () << "Starting Doppler:" << m_dx_two_way_dop;
}
//if (checked) {
// m_dx_two_way_dop = 2 * (m_dop - (m_dop00/2));
// qDebug () << "Starting Doppler:" << m_dx_two_way_dop;
//}
Q_EMIT tracking_update ();
}

View File

@ -59,7 +59,7 @@ private slots:
void on_rbFullTrack_clicked();
void on_rbOwnEcho_clicked();
void on_rbNoDoppler_clicked();
void on_rbOnDxEcho_clicked(bool);
void on_rbOnDxEcho_clicked();
void on_rbCallDx_clicked();
void on_cbDopplerTracking_toggled(bool);
@ -75,7 +75,7 @@ private:
qint32 m_DopplerMethod;
int m_dop;
int m_dop00;
int m_dx_two_way_dop;
//int m_dx_two_way_dop;
};
inline

View File

@ -566,15 +566,6 @@ MainWindow::MainWindow(QDir const& temp_directory, bool multiple,
} else if (text.isEmpty ()) {
ui->tx5->setCurrentText (text);
}
} else if (1 == ui->tabWidget->currentIndex ()) {
if (!text.isEmpty ()) {
ui->freeTextMsg->setCurrentText (text);
}
if (send) {
ui->rbFreeText->click ();
} else if (text.isEmpty ()) {
ui->freeTextMsg->setCurrentText (text);
}
}
QApplication::alert (this);
});
@ -811,17 +802,11 @@ MainWindow::MainWindow(QDir const& temp_directory, bool multiple,
ui->tx4->setValidator (new QRegExpValidator {message_alphabet, this});
ui->tx5->setValidator (new QRegExpValidator {message_alphabet, this});
ui->tx6->setValidator (new QRegExpValidator {message_alphabet, this});
ui->freeTextMsg->setValidator (new QRegExpValidator {message_alphabet, this});
// Free text macros model to widget hook up.
ui->tx5->setModel (m_config.macros ());
connect (ui->tx5->lineEdit(), &QLineEdit::editingFinished,
[this] () {on_tx5_currentTextChanged (ui->tx5->lineEdit()->text());});
ui->freeTextMsg->setModel (m_config.macros ());
connect (ui->freeTextMsg->lineEdit ()
, &QLineEdit::editingFinished
, [this] () {on_freeTextMsg_currentTextChanged (ui->freeTextMsg->lineEdit ()->text ());});
connect(&m_guiTimer, &QTimer::timeout, this, &MainWindow::guiUpdate);
m_guiTimer.start(100); //### Don't change the 100 ms! ###
@ -967,9 +952,6 @@ MainWindow::MainWindow(QDir const& temp_directory, bool multiple,
enable_DXCC_entity (m_config.DXCC ()); // sets text window proportions and (re)inits the logbook
ui->label_9->setStyleSheet("QLabel{color: #000000; background-color: #aabec8}");
ui->label_10->setStyleSheet("QLabel{color: #000000; background-color: #aabec8}");
// this must be done before initializing the mode as some modes need
// to turn off split on the rig e.g. WSPR
m_config.transceiver_online ();
@ -1127,7 +1109,6 @@ void MainWindow::writeSettings()
m_settings->setValue ("MsgAvgDisplayed", m_msgAvgWidget && m_msgAvgWidget->isVisible ());
m_settings->setValue ("FoxLogDisplayed", m_foxLogWindow && m_foxLogWindow->isVisible ());
m_settings->setValue ("ContestLogDisplayed", m_contestLogWindow && m_contestLogWindow->isVisible ());
m_settings->setValue ("FreeText", ui->freeTextMsg->currentText ());
m_settings->setValue("ShowMenus",ui->cbMenus->isChecked());
m_settings->setValue("CallFirst",ui->cbFirst->isChecked());
m_settings->setValue("HoundSort",ui->comboBoxHoundSort->currentIndex());
@ -1147,6 +1128,8 @@ void MainWindow::writeSettings()
m_settings->setValue("RxFreq",ui->RxFreqSpinBox->value());
m_settings->setValue("TxFreq",ui->TxFreqSpinBox->value());
m_settings->setValue("WSPRfreq",ui->WSPRfreqSpinBox->value());
m_settings->setValue("FST4W_RxFreq",ui->sbFST4W_RxFreq->value());
m_settings->setValue("FST4W_FTol",ui->sbFST4W_FTol->value());
m_settings->setValue("SubMode",ui->sbSubmode->value());
m_settings->setValue("DTtol",m_DTtol);
m_settings->setValue("Ftol", ui->sbFtol->value ());
@ -1162,6 +1145,7 @@ void MainWindow::writeSettings()
m_settings->setValue("OutBufSize",outBufSize);
m_settings->setValue ("HoldTxFreq", ui->cbHoldTxFreq->isChecked ());
m_settings->setValue("PctTx", ui->sbTxPercent->value ());
m_settings->setValue("RoundRobin",ui->RoundRobin->currentText());
m_settings->setValue("dBm",m_dBm);
m_settings->setValue("RR73",m_send_RR73);
m_settings->setValue ("WSPRPreferType1", ui->WSPR_prefer_type_1_check_box->isChecked ());
@ -1208,8 +1192,6 @@ void MainWindow::readSettings()
auto displayMsgAvg = m_settings->value ("MsgAvgDisplayed", false).toBool ();
auto displayFoxLog = m_settings->value ("FoxLogDisplayed", false).toBool ();
auto displayContestLog = m_settings->value ("ContestLogDisplayed", false).toBool ();
if (m_settings->contains ("FreeText")) ui->freeTextMsg->setCurrentText (
m_settings->value ("FreeText").toString ());
ui->cbMenus->setChecked(m_settings->value("ShowMenus",true).toBool());
ui->cbFirst->setChecked(m_settings->value("CallFirst",true).toBool());
ui->comboBoxHoundSort->setCurrentIndex(m_settings->value("HoundSort",3).toInt());
@ -1233,8 +1215,11 @@ void MainWindow::readSettings()
ui->actionSave_all->setChecked(m_settings->value("SaveAll",false).toBool());
ui->RxFreqSpinBox->setValue(0); // ensure a change is signaled
ui->RxFreqSpinBox->setValue(m_settings->value("RxFreq",1500).toInt());
ui->sbFST4W_RxFreq->setValue(0);
ui->sbFST4W_RxFreq->setValue(m_settings->value("FST4W_RxFreq",1500).toInt());
m_nSubMode=m_settings->value("SubMode",0).toInt();
ui->sbFtol->setValue (m_settings->value("Ftol", 50).toInt());
ui->sbFST4W_FTol->setValue(m_settings->value("FST4W_FTol",100).toInt());
m_minSync=m_settings->value("MinSync",0).toInt();
ui->syncSpinBox->setValue(m_minSync);
ui->cbAutoSeq->setChecked (m_settings->value ("AutoSeq", false).toBool());
@ -1254,6 +1239,7 @@ void MainWindow::readSettings()
m_ndepth=m_settings->value("NDepth",3).toInt();
ui->sbTxPercent->setValue (m_settings->value ("PctTx", 20).toInt ());
on_sbTxPercent_valueChanged (ui->sbTxPercent->value ());
ui->RoundRobin->setCurrentText(m_settings->value("RoundRobin",tr("Random")).toString());
m_dBm=m_settings->value("dBm",37).toInt();
m_send_RR73=m_settings->value("RR73",false).toBool();
if(m_send_RR73) {
@ -1902,7 +1888,7 @@ void MainWindow::on_monitorButton_clicked (bool checked)
on_RxFreqSpinBox_valueChanged (ui->RxFreqSpinBox->value ());
}
//Get Configuration in/out of strict split and mode checking
Q_EMIT m_config.sync_transceiver (true, checked);
m_config.sync_transceiver (true, checked);
} else {
ui->monitorButton->setChecked (false); // disallow
}
@ -2125,9 +2111,6 @@ void MainWindow::keyPressEvent (QKeyEvent * e)
if(ui->tabWidget->currentIndex()==0) {
ui->tx5->clearEditText();
ui->tx5->setFocus();
} else {
ui->freeTextMsg->clearEditText();
ui->freeTextMsg->setFocus();
}
return;
}
@ -2223,7 +2206,7 @@ void MainWindow::displayDialFrequency ()
{
// only change this when necessary as we get called a lot and it
// would trash any user input to the band combo box line edit
ui->bandComboBox->setCurrentText (band_name);
ui->bandComboBox->setCurrentText (band_name.size () ? band_name : m_config.bands ()->oob ());
m_wideGraph->setRxBand (band_name);
m_lastBand = band_name;
band_changed(dial_frequency);
@ -2487,9 +2470,9 @@ void MainWindow::on_actionFT8_DXpedition_Mode_User_Guide_triggered()
QDesktopServices::openUrl (QUrl {"http://physics.princeton.edu/pulsar/k1jt/FT8_DXpedition_Mode.pdf"});
}
void MainWindow::on_actionQuick_Start_Guide_v2_triggered()
void MainWindow::on_actionQuick_Start_Guide_triggered()
{
QDesktopServices::openUrl (QUrl {"https://physics.princeton.edu/pulsar/k1jt/Quick_Start_WSJT-X_2.0.pdf"});
QDesktopServices::openUrl (QUrl {"https://physics.princeton.edu/pulsar/k1jt/FST4_Quick_Start.pdf"});
}
void MainWindow::on_actionOnline_User_Guide_triggered() //Display manual
@ -2607,9 +2590,7 @@ void MainWindow::hideMenus(bool checked)
}
ui->decodedTextLabel->setVisible(!checked);
ui->gridLayout_5->layout()->setSpacing(spacing);
ui->horizontalLayout->layout()->setSpacing(spacing);
ui->horizontalLayout_2->layout()->setSpacing(spacing);
ui->horizontalLayout_3->layout()->setSpacing(spacing);
ui->horizontalLayout_5->layout()->setSpacing(spacing);
ui->horizontalLayout_6->layout()->setSpacing(spacing);
ui->horizontalLayout_7->layout()->setSpacing(spacing);
@ -2623,7 +2604,6 @@ void MainWindow::hideMenus(bool checked)
ui->verticalLayout->layout()->setSpacing(spacing);
ui->verticalLayout_2->layout()->setSpacing(spacing);
ui->verticalLayout_3->layout()->setSpacing(spacing);
ui->verticalLayout_4->layout()->setSpacing(spacing);
ui->verticalLayout_5->layout()->setSpacing(spacing);
ui->verticalLayout_7->layout()->setSpacing(spacing);
ui->verticalLayout_8->layout()->setSpacing(spacing);
@ -3088,6 +3068,7 @@ void MainWindow::decode() //decode()
dec_data.params.ntol=20;
dec_data.params.naggressive=0;
}
if(m_mode=="FST4W") dec_data.params.ntol=ui->sbFST4W_FTol->value ();
if(dec_data.params.nutc < m_nutc0) m_RxLog = 1; //Date and Time to file "ALL.TXT".
if(dec_data.params.newdat==1 and !m_diskData) m_nutc0=dec_data.params.nutc;
dec_data.params.ntxmode=9;
@ -3637,7 +3618,6 @@ void MainWindow::pskPost (DecodedText const& decodedtext)
}
int snr = decodedtext.snr();
Frequency frequency = m_freqNominal + audioFrequency;
pskSetLocal ();
if(grid.contains (grid_regexp)) {
// qDebug() << "To PSKreporter:" << deCall << grid << frequency << msgmode << snr;
if (!m_psk_Reporter.addRemoteStation (deCall, grid, frequency, msgmode, snr))
@ -3849,8 +3829,6 @@ void MainWindow::guiUpdate()
if(m_ntx == 4) txMsg=ui->tx4->text();
if(m_ntx == 5) txMsg=ui->tx5->currentText();
if(m_ntx == 6) txMsg=ui->tx6->text();
if(m_ntx == 7) txMsg=ui->genMsg->text();
if(m_ntx == 8) txMsg=ui->freeTextMsg->currentText();
int msgLength=txMsg.trimmed().length();
if(msgLength==0 and !m_tune) on_stopTxButton_clicked();
@ -3900,7 +3878,7 @@ void MainWindow::guiUpdate()
}
setXIT (ui->TxFreqSpinBox->value ());
Q_EMIT m_config.transceiver_ptt (true); //Assert the PTT
m_config.transceiver_ptt (true); //Assert the PTT
m_tx_when_ready = true;
}
// if(!m_bTxTime and !m_tune and m_mode!="FT4") m_btxok=false; //Time to stop transmitting
@ -3950,8 +3928,6 @@ void MainWindow::guiUpdate()
if(m_ntx == 4) ba=ui->tx4->text().toLocal8Bit();
if(m_ntx == 5) ba=ui->tx5->currentText().toLocal8Bit();
if(m_ntx == 6) ba=ui->tx6->text().toLocal8Bit();
if(m_ntx == 7) ba=ui->genMsg->text().toLocal8Bit();
if(m_ntx == 8) ba=ui->freeTextMsg->currentText().toLocal8Bit();
}
ba2msg(ba,message);
@ -4002,7 +3978,7 @@ void MainWindow::guiUpdate()
}
if(m_modeTx=="FT8") {
if(SpecOp::FOX==m_config.special_op_id() and ui->tabWidget->currentIndex()==2) {
if(SpecOp::FOX==m_config.special_op_id() and ui->tabWidget->currentIndex()==1) {
foxTxSequencer();
} else {
int i3=0;
@ -4059,7 +4035,7 @@ void MainWindow::guiUpdate()
}
genfst4_(message,&ichk,msgsent,const_cast<char *> (fst4msgbits),
const_cast<int *>(itone), &iwspr, 37, 37);
int hmod=int(pow(2.0,double(m_nSubMode)));
int hmod=1; //No FST4/W submodes
int nsps=720;
if(m_TRperiod==30) nsps=1680;
if(m_TRperiod==60) nsps=3888;
@ -4078,18 +4054,6 @@ void MainWindow::guiUpdate()
&fsample,&hmod,&f0,&icmplx,foxcom_.wave,foxcom_.wave);
QString t = QString::fromStdString(message).trimmed();
bool both=(t=="CQ BOTH K1JT FN20" or t=="CQ BOTH K9AN EN50");
if(both) {
float wave_both[15*48000];
memcpy(wave_both,foxcom_.wave,4*15*48000); //Copy wave[] into wave_both[]
f0=f0 + 200 + 25;
hmod=2;
gen_fst4wave_(const_cast<int *>(itone),&nsym,&nsps,&nwave,
&fsample,&hmod,&f0,&icmplx,foxcom_.wave,foxcom_.wave);
for(int i=0; i<15*48000; i++) {
foxcom_.wave[i]=0.5*(wave_both[i] + foxcom_.wave[i]);
}
}
}
if(SpecOp::EU_VHF==m_config.special_op_id()) {
@ -4205,17 +4169,8 @@ void MainWindow::guiUpdate()
m_restart=false;
//----------------------------------------------------------------------
} else {
if (!m_auto && m_sentFirst73)
{
if (!m_auto && m_sentFirst73) {
m_sentFirst73 = false;
if (1 == ui->tabWidget->currentIndex())
{
ui->genMsg->setText(ui->tx6->text());
m_ntx=7;
m_QSOProgress = CALLING;
m_gen_message_is_cq = true;
ui->rbGenMsg->setChecked(true);
}
}
}
if (g_iptt == 1 && m_iptt0 == 0) {
@ -4280,9 +4235,10 @@ void MainWindow::guiUpdate()
}
}
//Once per second:
//Once per second (onesec)
if(nsec != m_sec0) {
// qDebug() << "onesec" << m_hsymStop << m_TRperiod;
// qDebug() << "AAA" << nsec;
if(m_mode=="FST4") sbFtolMaxVal();
m_currentBand=m_config.bands()->find(m_freqNominal);
if( SpecOp::HOUND == m_config.special_op_id() ) {
qint32 tHound=QDateTime::currentMSecsSinceEpoch()/1000 - m_tAutoOn;
@ -4315,7 +4271,7 @@ void MainWindow::guiUpdate()
if(m_transmitting) {
char s[42];
if(SpecOp::FOX==m_config.special_op_id() and ui->tabWidget->currentIndex()==2) {
if(SpecOp::FOX==m_config.special_op_id() and ui->tabWidget->currentIndex()==1) {
sprintf(s,"Tx: %d Slots",foxcom_.nslots);
} else {
sprintf(s,"Tx: %s",msgsent);
@ -4337,7 +4293,7 @@ void MainWindow::guiUpdate()
} else {
s[40]=0;
QString t{QString::fromLatin1(s)};
if(SpecOp::FOX==m_config.special_op_id() and ui->tabWidget->currentIndex()==2 and foxcom_.nslots==1) {
if(SpecOp::FOX==m_config.special_op_id() and ui->tabWidget->currentIndex()==1 and foxcom_.nslots==1) {
t=m_fm1.trimmed();
}
if(m_mode=="FT4") t="Tx: "+ m_currentMessage;
@ -4439,7 +4395,7 @@ void MainWindow::stopTx()
void MainWindow::stopTx2()
{
Q_EMIT m_config.transceiver_ptt (false); //Lower PTT
m_config.transceiver_ptt (false); //Lower PTT
if (m_mode == "JT9" && m_bFast9
&& ui->cbAutoSeq->isVisible () && ui->cbAutoSeq->isChecked()
&& m_ntx == 5 && m_nTx73 >= 5) {
@ -4824,7 +4780,8 @@ void MainWindow::processMessage (DecodedText const& message, Qt::KeyboardModifie
ui->TxFreqSpinBox->setValue(frequency);
}
if(m_mode != "JT4" && m_mode != "JT65" && !m_mode.startsWith ("JT9") &&
m_mode != "QRA64" && m_mode != "QRA66" && m_mode!="FT8" && m_mode!="FT4") {
m_mode != "QRA64" && m_mode != "QRA66" && m_mode!="FT8" &&
m_mode!="FT4" && m_mode!="FST4") {
return;
}
}
@ -4837,7 +4794,6 @@ void MainWindow::processMessage (DecodedText const& message, Qt::KeyboardModifie
// Determine appropriate response to received message
auto dtext = " " + message.string () + " ";
dtext=dtext.remove("<").remove(">");
int gen_msg {0};
if(dtext.contains (" " + m_baseCall + " ")
|| dtext.contains ("<" + m_baseCall + "> ")
//###??? || dtext.contains ("<" + m_baseCall + " " + hiscall + "> ")
@ -4896,57 +4852,52 @@ void MainWindow::processMessage (DecodedText const& message, Qt::KeyboardModifie
or bEU_VHF_w2 or (m_QSOProgress==CALLING))) {
if(message_words.at(3).contains(grid_regexp) and SpecOp::EU_VHF!=m_config.special_op_id()) {
if(SpecOp::NA_VHF==m_config.special_op_id() or SpecOp::WW_DIGI==m_config.special_op_id()){
gen_msg=setTxMsg(3);
setTxMsg(3);
m_QSOProgress=ROGER_REPORT;
} else {
if(m_mode=="JT65" and message_words.size()>4 and message_words.at(4)=="OOO") {
gen_msg=setTxMsg(3);
setTxMsg(3);
m_QSOProgress=ROGER_REPORT;
} else {
gen_msg=setTxMsg(2);
setTxMsg(2);
m_QSOProgress=REPORT;
}
}
} else if(w34.contains(grid_regexp) and SpecOp::EU_VHF==m_config.special_op_id()) {
if(nrpt==0) {
gen_msg=setTxMsg(2);
setTxMsg(2);
m_QSOProgress=REPORT;
} else {
if(w2=="R") {
gen_msg=setTxMsg(4);
setTxMsg(4);
m_QSOProgress=ROGERS;
} else {
gen_msg=setTxMsg(3);
setTxMsg(3);
m_QSOProgress=ROGER_REPORT;
}
}
} else if(SpecOp::RTTY == m_config.special_op_id() and bRTTY) {
if(w2=="R") {
gen_msg=setTxMsg(4);
setTxMsg(4);
m_QSOProgress=ROGERS;
} else {
gen_msg=setTxMsg(3);
setTxMsg(3);
m_QSOProgress=ROGER_REPORT;
}
m_xRcvd=t[n-2] + " " + t[n-1];
} else if(SpecOp::FIELD_DAY==m_config.special_op_id() and bFieldDay_msg) {
if(t0=="R") {
gen_msg=setTxMsg(4);
setTxMsg(4);
m_QSOProgress=ROGERS;
} else {
gen_msg=setTxMsg(3);
setTxMsg(3);
m_QSOProgress=ROGER_REPORT;
}
} else { // no grid on end of msg
QString r=message_words.at (3);
if(m_QSOProgress >= ROGER_REPORT && (r=="RRR" || r.toInt()==73 || "RR73" == r)) {
if(m_mode=="FT4" and r=="RR73") m_dateTimeRcvdRR73=QDateTime::currentDateTimeUtc();
if(ui->tabWidget->currentIndex()==1) {
gen_msg = 5;
if (ui->rbGenMsg->isChecked ()) m_ntx=7;
m_gen_message_is_cq = false;
} else {
m_bTUmsg=false;
m_nextCall=""; //### Temporary: disable use of "TU;" message
if(SpecOp::RTTY == m_config.special_op_id() and m_nextCall!="") {
@ -4967,7 +4918,6 @@ void MainWindow::processMessage (DecodedText const& message, Qt::KeyboardModifie
ui->txrb5->setChecked(true);
}
}
}
m_QSOProgress = SIGNOFF;
} else if((m_QSOProgress >= REPORT
|| (m_QSOProgress >= REPLYING &&
@ -4981,24 +4931,19 @@ void MainWindow::processMessage (DecodedText const& message, Qt::KeyboardModifie
if(nRpt>=529 and nRpt<=599) m_xRcvd=t[n-2] + " " + t[n-1];
}
ui->txrb4->setChecked(true);
if(ui->tabWidget->currentIndex()==1) {
gen_msg = 4;
m_ntx=7;
m_gen_message_is_cq = false;
}
} else if(m_QSOProgress>=CALLING and
((r.toInt()>=-50 && r.toInt()<=49) or (r.toInt()>=529 && r.toInt()<=599))) {
if(SpecOp::EU_VHF==m_config.special_op_id() or
SpecOp::FIELD_DAY==m_config.special_op_id() or
SpecOp::RTTY==m_config.special_op_id()) {
gen_msg=setTxMsg(2);
setTxMsg(2);
m_QSOProgress=REPORT;
} else {
if(r.left(2)=="R-" or r.left(2)=="R+") {
gen_msg=setTxMsg(4);
setTxMsg(4);
m_QSOProgress=ROGERS;
} else {
gen_msg=setTxMsg(3);
setTxMsg(3);
m_QSOProgress=ROGER_REPORT;
}
}
@ -5011,15 +4956,8 @@ void MainWindow::processMessage (DecodedText const& message, Qt::KeyboardModifie
&& message_words.size () > 2 && message_words.at (1).contains (m_baseCall)
&& message_words.at (2) == "73") {
// 73 back to compound call holder
if(ui->tabWidget->currentIndex()==1) {
gen_msg = 5;
if (ui->rbGenMsg->isChecked ()) m_ntx=7;
m_gen_message_is_cq = false;
}
else {
m_ntx=5;
ui->txrb5->setChecked(true);
}
m_ntx=5;
ui->txrb5->setChecked(true);
m_QSOProgress = SIGNOFF;
}
else if (!(m_bAutoReply && (m_QSOProgress > CALLING))) {
@ -5029,21 +4967,10 @@ void MainWindow::processMessage (DecodedText const& message, Qt::KeyboardModifie
m_ntx=3;
m_QSOProgress = ROGER_REPORT;
ui->txrb3->setChecked (true);
if (ui->tabWidget->currentIndex () == 1) {
gen_msg = 3;
m_ntx = 7;
m_gen_message_is_cq = false;
}
} else if (!is_73) { // don't respond to sign off messages
m_ntx=2;
m_QSOProgress = REPORT;
ui->txrb2->setChecked(true);
if(ui->tabWidget->currentIndex()==1) {
gen_msg = 2;
m_ntx=7;
m_gen_message_is_cq = false;
}
if (m_bDoubleClickAfterCQnnn and m_transmitting) {
on_stopTxButton_clicked();
TxAgainTimer.start(1500);
@ -5072,14 +4999,8 @@ void MainWindow::processMessage (DecodedText const& message, Qt::KeyboardModifie
else if (firstcall == "DE" && message_words.size () > 3 && message_words.at (3) == "73") {
if (m_QSOProgress >= ROGERS && base_call == qso_partner_base_call && m_currentMessageType) {
// 73 back to compound call holder
if(ui->tabWidget->currentIndex()==1) {
gen_msg = 5;
m_ntx=7;
m_gen_message_is_cq = false;
} else {
m_ntx=5;
ui->txrb5->setChecked(true);
}
m_ntx=5;
ui->txrb5->setChecked(true);
m_QSOProgress = SIGNOFF;
} else {
// treat like a CQ/QRZ
@ -5092,22 +5013,11 @@ void MainWindow::processMessage (DecodedText const& message, Qt::KeyboardModifie
m_QSOProgress = REPORT;
ui->txrb2->setChecked (true);
}
if(ui->tabWidget->currentIndex()==1) {
gen_msg = 1;
m_ntx=7;
m_gen_message_is_cq = false;
}
}
}
else if (is_73 && !message.isStandardMessage ()) {
if(ui->tabWidget->currentIndex()==1) {
gen_msg = 5;
if (ui->rbGenMsg->isChecked ()) m_ntx=7;
m_gen_message_is_cq = false;
} else {
m_ntx=5;
ui->txrb5->setChecked(true);
}
m_ntx=5;
ui->txrb5->setChecked(true);
m_QSOProgress = SIGNOFF;
} else {
// just work them
@ -5120,11 +5030,6 @@ void MainWindow::processMessage (DecodedText const& message, Qt::KeyboardModifie
m_QSOProgress = REPORT;
ui->txrb2->setChecked (true);
}
if (1 == ui->tabWidget->currentIndex ()) {
gen_msg = m_ntx;
m_ntx=7;
m_gen_message_is_cq = false;
}
}
// if we get here then we are reacting to the message
if (m_bAutoReply) m_bCallingCQ = CALLING == m_QSOProgress;
@ -5178,29 +5083,17 @@ void MainWindow::processMessage (DecodedText const& message, Qt::KeyboardModifie
m_bTUmsg=false; //### Temporary: disable use of "TU;" messages
if (!m_nTx73 and !m_bTUmsg) {
genStdMsgs(rpt);
if (gen_msg) {
switch (gen_msg) {
case 1: ui->genMsg->setText (ui->tx1->text ()); break;
case 2: ui->genMsg->setText (ui->tx2->text ()); break;
case 3: ui->genMsg->setText (ui->tx3->text ()); break;
case 4: ui->genMsg->setText (ui->tx4->text ()); break;
case 5: ui->genMsg->setText (ui->tx5->currentText ()); break;
}
if (gen_msg != 5) { // allow user to pre-select a free message
ui->rbGenMsg->setChecked (true);
}
}
}
if(m_transmitting) m_restart=true;
if (ui->cbAutoSeq->isVisible () && ui->cbAutoSeq->isChecked ()
&& !m_bDoubleClicked && m_mode!="FT4") {
return;
}
if(m_config.quick_call()) auto_tx_mode(true);
if(m_config.quick_call() && m_bDoubleClicked) auto_tx_mode(true);
m_bDoubleClicked=false;
}
int MainWindow::setTxMsg(int n)
void MainWindow::setTxMsg(int n)
{
m_ntx=n;
if(n==1) ui->txrb1->setChecked(true);
@ -5209,11 +5102,6 @@ int MainWindow::setTxMsg(int n)
if(n==4) ui->txrb4->setChecked(true);
if(n==5) ui->txrb5->setChecked(true);
if(n==6) ui->txrb6->setChecked(true);
if(ui->tabWidget->currentIndex()==1) {
m_ntx=7; //### FIX THIS ###
m_gen_message_is_cq = false;
}
return n;
}
void MainWindow::genCQMsg ()
@ -5305,7 +5193,6 @@ void MainWindow::genStdMsgs(QString rpt, bool unconditional)
ui->tx3->clear ();
ui->tx4->clear ();
if(unconditional) ui->tx5->lineEdit ()->clear (); //Test if it needs sending again
ui->genMsg->clear ();
m_gen_message_is_cq = false;
return;
}
@ -5547,19 +5434,12 @@ void MainWindow::clearDX ()
m_qsoStop.clear ();
m_inQSOwith.clear();
genStdMsgs (QString {});
if (ui->tabWidget->currentIndex() == 1) {
ui->genMsg->setText(ui->tx6->text());
m_ntx=7;
m_gen_message_is_cq = true;
ui->rbGenMsg->setChecked(true);
if (m_mode=="FT8" and SpecOp::HOUND == m_config.special_op_id()) {
m_ntx=1;
ui->txrb1->setChecked(true);
} else {
if (m_mode=="FT8" and SpecOp::HOUND == m_config.special_op_id()) {
m_ntx=1;
ui->txrb1->setChecked(true);
} else {
m_ntx=6;
ui->txrb6->setChecked(true);
}
m_ntx=6;
ui->txrb6->setChecked(true);
}
m_QSOProgress = CALLING;
}
@ -6024,23 +5904,21 @@ void MainWindow::displayWidgets(qint64 n)
void MainWindow::on_actionFST4_triggered()
{
int nsub=m_nSubMode;
on_actionJT65_triggered();
ui->label_6->setText(tr ("Band Activity"));
ui->label_7->setText(tr ("Rx Frequency"));
ui->sbSubmode->setMaximum(3);
m_nSubMode=nsub;
ui->sbSubmode->setValue(m_nSubMode);
m_mode="FST4";
m_modeTx="FST4";
ui->actionFST4->setChecked(true);
m_nsps=6912; //For symspec only
m_FFTSize = m_nsps / 2;
Q_EMIT FFTSize(m_FFTSize);
ui->label_6->setText(tr ("Band Activity"));
ui->label_7->setText(tr ("Rx Frequency"));
WSPR_config(false);
bool bVHF=m_config.enable_VHF_features();
// 0123456789012345678901234567890123
displayWidgets(nWidgets("1111110001001111000100000001000000"));
setup_status_bar (bVHF);
displayWidgets(nWidgets("1111110001001110000100000001000000"));
setup_status_bar(false);
ui->sbTR->values ({15, 30, 60, 120, 300, 900, 1800});
on_sbTR_valueChanged (ui->sbTR->value());
sbFtolMaxVal();
ui->cbAutoSeq->setChecked(true);
m_wideGraph->setMode(m_mode);
m_wideGraph->setModeTx(m_modeTx);
@ -6053,25 +5931,25 @@ void MainWindow::on_actionFST4_triggered()
void MainWindow::on_actionFST4W_triggered()
{
on_actionFST4_triggered();
m_mode="FST4W";
m_modeTx="FST4W";
WSPR_config(true);
ui->actionFST4W->setChecked(true);
m_nsps=6912; //For symspec only
m_FFTSize = m_nsps / 2;
Q_EMIT FFTSize(m_FFTSize);
WSPR_config(true);
// 0123456789012345678901234567890123
displayWidgets(nWidgets("0000000000000000010100000000000001"));
bool bVHF=m_config.enable_VHF_features();
setup_status_bar (bVHF);
m_nSubMode=0;
ui->sbSubmode->setValue(m_nSubMode);
setup_status_bar(false);
ui->band_hopping_group_box->setChecked(false);
ui->band_hopping_group_box->setVisible(false);
on_sbTR_FST4W_valueChanged (ui->sbTR_FST4W->value ());
ui->sbSubmode->setMaximum(3);
m_wideGraph->setMode(m_mode);
m_wideGraph->setModeTx(m_modeTx);
m_wideGraph->setPeriod(m_TRperiod,6912);
m_wideGraph->setTxFreq(ui->WSPRfreqSpinBox->value());
m_wideGraph->setRxFreq(ui->sbFST4W_RxFreq->value());
m_wideGraph->setTol(ui->sbFST4W_FTol->value());
ui->sbFtol->setValue(100);
ui->RxFreqSpinBox->setValue(1500);
switch_mode (Modes::FST4W);
@ -6173,7 +6051,7 @@ void MainWindow::on_actionFT8_triggered()
ui->txFirstCheckBox->setEnabled(false);
ui->cbHoldTxFreq->setChecked(true);
ui->cbAutoSeq->setEnabled(false);
ui->tabWidget->setCurrentIndex(2);
ui->tabWidget->setCurrentIndex(1);
ui->TxFreqSpinBox->setValue(300);
displayWidgets(nWidgets("1110100001001110000100000000001000"));
ui->labDXped->setText(tr ("Fox"));
@ -6667,14 +6545,15 @@ void MainWindow::switch_mode (Mode mode)
m_fastGraph->setMode(m_mode);
m_config.frequencies ()->filter (m_config.region (), mode);
auto const& row = m_config.frequencies ()->best_working_frequency (m_freqNominal);
ui->bandComboBox->setCurrentIndex (row);
if (row >= 0) {
ui->bandComboBox->setCurrentIndex (row);
on_bandComboBox_activated (row);
}
ui->rptSpinBox->setSingleStep(1);
ui->rptSpinBox->setMinimum(-50);
ui->rptSpinBox->setMaximum(49);
ui->sbFtol->values ({10, 20, 50, 100, 200, 500, 1000});
ui->sbFtol->values ({1, 2, 5, 10, 20, 50, 100, 200, 300, 400, 500, 1000});
ui->sbFST4W_FTol->values({1, 2, 5, 10, 20, 50, 100});
if(m_mode=="MSK144") {
ui->RxFreqSpinBox->setMinimum(1400);
ui->RxFreqSpinBox->setMaximum(1600);
@ -6707,9 +6586,12 @@ void MainWindow::WSPR_config(bool b)
ui->label_7->setVisible(!b and ui->cbMenus->isChecked());
ui->logQSOButton->setVisible(!b);
ui->DecodeButton->setEnabled(!b);
ui->sbTxPercent->setEnabled (m_mode != "FST4W" || tr ("Random") == ui->RoundRobin->currentText ());
bool bFST4W=(m_mode=="FST4W");
ui->sbTxPercent->setEnabled(!bFST4W or (tr("Random") == ui->RoundRobin->currentText()));
ui->band_hopping_group_box->setVisible(true);
ui->RoundRobin->setVisible(m_mode=="FST4W");
ui->RoundRobin->setVisible(bFST4W);
ui->sbFST4W_RxFreq->setVisible(bFST4W);
ui->sbFST4W_FTol->setVisible(bFST4W);
ui->RoundRobin->lineEdit()->setAlignment(Qt::AlignCenter);
if(b and m_mode!="Echo" and m_mode!="FST4W") {
QString t="UTC dB DT Freq Drift Call Grid dBm ";
@ -6717,7 +6599,7 @@ void MainWindow::WSPR_config(bool b)
if(!m_config.miles()) t += " km";
ui->decodedTextLabel->setText(t);
if (m_config.is_transceiver_online ()) {
Q_EMIT m_config.transceiver_tx_frequency (0); // turn off split
m_config.transceiver_tx_frequency (0); // turn off split
}
m_bSimplex = true;
} else
@ -6863,17 +6745,20 @@ void MainWindow::on_bandComboBox_currentIndexChanged (int index)
// Lookup band
auto const& band = m_config.bands ()->find (frequency);
if (!band.isEmpty ())
ui->bandComboBox->setCurrentText (band.size () ? band : m_config.bands ()->oob ());
displayDialFrequency ();
}
void MainWindow::on_bandComboBox_editTextChanged (QString const& text)
{
if (text.size () && m_config.bands ()->oob () != text)
{
ui->bandComboBox->lineEdit ()->setStyleSheet ({});
ui->bandComboBox->setCurrentText (band);
}
else
{
ui->bandComboBox->lineEdit ()->setStyleSheet ("QLineEdit {color: yellow; background-color : red;}");
ui->bandComboBox->setCurrentText (m_config.bands ()->oob ());
}
displayDialFrequency ();
}
void MainWindow::on_bandComboBox_activated (int index)
@ -6945,111 +6830,6 @@ void MainWindow::enable_DXCC_entity (bool on)
updateGeometry ();
}
void MainWindow::on_pbCallCQ_clicked()
{
genStdMsgs(m_rpt);
ui->genMsg->setText(ui->tx6->text());
m_ntx=7;
m_QSOProgress = CALLING;
m_gen_message_is_cq = true;
ui->rbGenMsg->setChecked(true);
if(m_transmitting) m_restart=true;
set_dateTimeQSO(-1);
}
void MainWindow::on_pbAnswerCaller_clicked()
{
genStdMsgs(m_rpt);
QString t=ui->tx3->text();
int i0=t.indexOf(" R-");
if(i0<0) i0=t.indexOf(" R+");
t=t.mid(0,i0+1)+t.mid(i0+2,3);
ui->genMsg->setText(t);
m_ntx=7;
m_QSOProgress = REPORT;
m_gen_message_is_cq = false;
ui->rbGenMsg->setChecked(true);
if(m_transmitting) m_restart=true;
set_dateTimeQSO(2);
}
void MainWindow::on_pbSendRRR_clicked()
{
genStdMsgs(m_rpt);
ui->genMsg->setText(ui->tx4->text());
m_ntx=7;
m_QSOProgress = ROGERS;
m_gen_message_is_cq = false;
ui->rbGenMsg->setChecked(true);
if(m_transmitting) m_restart=true;
}
void MainWindow::on_pbAnswerCQ_clicked()
{
genStdMsgs(m_rpt);
ui->genMsg->setText(ui->tx1->text());
QString t=ui->tx2->text();
int i0=t.indexOf("/");
int i1=t.indexOf(" ");
if(i0>0 and i0<i1) ui->genMsg->setText(t);
m_ntx=7;
m_QSOProgress = REPLYING;
m_gen_message_is_cq = false;
ui->rbGenMsg->setChecked(true);
if(m_transmitting) m_restart=true;
}
void MainWindow::on_pbSendReport_clicked()
{
genStdMsgs(m_rpt);
ui->genMsg->setText(ui->tx3->text());
m_ntx=7;
m_QSOProgress = ROGER_REPORT;
m_gen_message_is_cq = false;
ui->rbGenMsg->setChecked(true);
if(m_transmitting) m_restart=true;
set_dateTimeQSO(3);
}
void MainWindow::on_pbSend73_clicked()
{
genStdMsgs(m_rpt);
ui->genMsg->setText(ui->tx5->currentText());
m_ntx=7;
m_QSOProgress = SIGNOFF;
m_gen_message_is_cq = false;
ui->rbGenMsg->setChecked(true);
if(m_transmitting) m_restart=true;
}
void MainWindow::on_rbGenMsg_clicked(bool checked)
{
m_freeText=!checked;
if(!m_freeText) {
if(m_ntx != 7 && m_transmitting) m_restart=true;
m_ntx=7;
// would like to set m_QSOProgress but what to? So leave alone and
// assume it is correct
}
}
void MainWindow::on_rbFreeText_clicked(bool checked)
{
m_freeText=checked;
if(m_freeText) {
m_ntx=8;
// would like to set m_QSOProgress but what to? So leave alone and
// assume it is correct. Perhaps should store old value to be
// restored above in on_rbGenMsg_clicked
if (m_transmitting) m_restart=true;
}
}
void MainWindow::on_freeTextMsg_currentTextChanged (QString const& text)
{
msgtype(text, ui->freeTextMsg->lineEdit ());
}
void MainWindow::on_rptSpinBox_valueChanged(int n)
{
int step=ui->rptSpinBox->singleStep();
@ -7136,7 +6916,7 @@ void MainWindow::rigOpen ()
ui->readFreq->setText ("");
ui->readFreq->setEnabled (true);
m_config.transceiver_online ();
Q_EMIT m_config.sync_transceiver (true, true);
m_config.sync_transceiver (true, true);
}
void MainWindow::on_pbR2T_clicked()
@ -7159,7 +6939,7 @@ void MainWindow::on_readFreq_clicked()
if (m_config.transceiver_online ())
{
Q_EMIT m_config.sync_transceiver (true, true);
m_config.sync_transceiver (true, true);
}
}
@ -7209,7 +6989,7 @@ void MainWindow::setXIT(int n, Frequency base)
// frequency
m_freqTxNominal = base + m_XIT;
if (m_astroWidget) m_astroWidget->nominal_frequency (m_freqNominal, m_freqTxNominal);
Q_EMIT m_config.transceiver_tx_frequency (m_freqTxNominal + m_astroCorrection.tx);
m_config.transceiver_tx_frequency (m_freqTxNominal + m_astroCorrection.tx);
}
}
//Now set the audio Tx freq
@ -7405,7 +7185,7 @@ void MainWindow::transmit (double snr)
if(m_TRperiod==300) nsps=21504;
if(m_TRperiod==900) nsps=66560;
if(m_TRperiod==1800) nsps=134400;
int hmod=int(pow(2.0,double(m_nSubMode)));
int hmod=1; //No FST4/W submodes
double dfreq=hmod*12000.0/nsps;
double f0=ui->WSPRfreqSpinBox->value() - m_XIT;
if(!m_tune) f0 += + 1.5*dfreq;
@ -7716,6 +7496,7 @@ void MainWindow::on_sbTR_valueChanged(int value)
m_wideGraph->setPeriod (value, m_nsps);
progressBar.setMaximum (value);
}
if(m_mode=="FST4") sbFtolMaxVal();
if(m_monitoring) {
on_stopButton_clicked();
on_monitorButton_clicked(true);
@ -7726,6 +7507,14 @@ void MainWindow::on_sbTR_valueChanged(int value)
statusUpdate ();
}
void MainWindow::sbFtolMaxVal()
{
if(m_TRperiod<=60) ui->sbFtol->setMaximum(1000);
if(m_TRperiod==120) ui->sbFtol->setMaximum(500);
if(m_TRperiod==300) ui->sbFtol->setMaximum(200);
if(m_TRperiod>=900) ui->sbFtol->setMaximum(100);
}
void MainWindow::on_sbTR_FST4W_valueChanged(int value)
{
on_sbTR_valueChanged(value);
@ -8197,6 +7986,19 @@ void MainWindow::on_WSPRfreqSpinBox_valueChanged(int n)
ui->TxFreqSpinBox->setValue(n);
}
void MainWindow::on_sbFST4W_RxFreq_valueChanged(int n)
{
m_wideGraph->setRxFreq(n);
statusUpdate ();
}
void MainWindow::on_sbFST4W_FTol_valueChanged(int n)
{
ui->sbFST4W_RxFreq->setSingleStep(n);
m_wideGraph->setTol(n);
statusUpdate ();
}
void MainWindow::on_pbTxNext_clicked(bool b)
{
if (b && !ui->autoButton->isChecked ())
@ -8362,11 +8164,11 @@ void MainWindow::setRig (Frequency f)
{
if (m_transmitting && m_config.split_mode ())
{
Q_EMIT m_config.transceiver_tx_frequency (m_freqTxNominal + m_astroCorrection.tx);
m_config.transceiver_tx_frequency (m_freqTxNominal + m_astroCorrection.tx);
}
else
{
Q_EMIT m_config.transceiver_frequency (m_freqNominal + m_astroCorrection.rx);
m_config.transceiver_frequency (m_freqNominal + m_astroCorrection.rx);
}
}
}

View File

@ -151,7 +151,7 @@ private slots:
void on_stopButton_clicked();
void on_actionRelease_Notes_triggered ();
void on_actionFT8_DXpedition_Mode_User_Guide_triggered();
void on_actionQuick_Start_Guide_v2_triggered();
void on_actionQuick_Start_Guide_triggered();
void on_actionOnline_User_Guide_triggered();
void on_actionLocal_User_Guide_triggered();
void on_actionWide_Waterfall_triggered();
@ -223,15 +223,6 @@ private slots:
void startP1();
void stopTx();
void stopTx2();
void on_pbCallCQ_clicked();
void on_pbAnswerCaller_clicked();
void on_pbSendRRR_clicked();
void on_pbAnswerCQ_clicked();
void on_pbSendReport_clicked();
void on_pbSend73_clicked();
void on_rbGenMsg_clicked(bool checked);
void on_rbFreeText_clicked(bool checked);
void on_freeTextMsg_currentTextChanged (QString const&);
void on_rptSpinBox_valueChanged(int n);
void killFile();
void on_tuneButton_clicked (bool);
@ -246,6 +237,7 @@ private slots:
, QString const& exchange_sent, QString const& exchange_rcvd
, QString const& propmode, QByteArray const& ADIF);
void on_bandComboBox_currentIndexChanged (int index);
void on_bandComboBox_editTextChanged (QString const& text);
void on_bandComboBox_activated (int index);
void on_readFreq_clicked();
void on_pbTxMode_clicked();
@ -289,6 +281,8 @@ private slots:
void TxAgain();
void uploadResponse(QString response);
void on_WSPRfreqSpinBox_valueChanged(int n);
void on_sbFST4W_RxFreq_valueChanged(int n);
void on_sbFST4W_FTol_valueChanged(int n);
void on_pbTxNext_clicked(bool b);
void on_actionEcho_Graph_triggered();
void on_actionEcho_triggered();
@ -319,7 +313,8 @@ private slots:
void checkMSK144ContestType();
void on_pbBestSP_clicked();
void on_RoundRobin_currentTextChanged(QString text);
int setTxMsg(int n);
void setTxMsg(int n);
void sbFtolMaxVal();
bool stdCall(QString const& w);
void remote_configure (QString const& mode, quint32 frequency_tolerance, QString const& submode
, bool fast_mode, quint32 tr_period, quint32 rx_df, QString const& dx_call

View File

@ -721,6 +721,9 @@ QPushButton[state=&quot;ok&quot;] {
<property name="toolTip">
<string>Set Tx frequency to Rx Frequency</string>
</property>
<property name="accessibleName">
<string>Set Tx frequency to Rx Frequency</string>
</property>
<property name="text">
<string>▲</string>
</property>
@ -771,6 +774,9 @@ QPushButton[state=&quot;ok&quot;] {
<property name="toolTip">
<string>Set Rx frequency to Tx Frequency</string>
</property>
<property name="accessibleName">
<string>Set Rx frequency to Tx Frequency</string>
</property>
<property name="text">
<string>▼</string>
</property>
@ -1507,274 +1513,9 @@ list. The list can be maintained in Settings (F2).</string>
</item>
</layout>
</widget>
<widget class="QWidget" name="tab_2">
<attribute name="title">
<string>2</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_4">
<property name="leftMargin">
<number>6</number>
</property>
<property name="topMargin">
<number>6</number>
</property>
<property name="rightMargin">
<number>6</number>
</property>
<property name="bottomMargin">
<number>6</number>
</property>
<item>
<layout class="QGridLayout" name="gridLayout_4">
<property name="horizontalSpacing">
<number>0</number>
</property>
<item row="0" column="0">
<widget class="QLabel" name="label_9">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>2</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>30</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>30</height>
</size>
</property>
<property name="text">
<string>Calling CQ </string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QPushButton" name="pbCallCQ">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>2</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Generate a CQ message</string>
</property>
<property name="text">
<string>CQ</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QPushButton" name="pbSendRRR">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>2</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Generate message with RRR</string>
</property>
<property name="text">
<string>RRR</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QPushButton" name="pbAnswerCaller">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>2</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Generate message with report</string>
</property>
<property name="text">
<string>dB</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_10">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>2</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>30</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>30</height>
</size>
</property>
<property name="text">
<string>Answering CQ</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QPushButton" name="pbAnswerCQ">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>2</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Generate message for replying to a CQ</string>
</property>
<property name="text">
<string>Grid</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QPushButton" name="pbSendReport">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>2</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Generate message with R+report</string>
</property>
<property name="text">
<string>R+dB</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QPushButton" name="pbSend73">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>2</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Generate message with 73</string>
</property>
<property name="text">
<string>73</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QLineEdit" name="genMsg">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>3</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
</widget>
</item>
<item>
<widget class="QRadioButton" name="rbGenMsg">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>1</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>26</height>
</size>
</property>
<property name="toolTip">
<string>Send this standard (generated) message</string>
</property>
<property name="text">
<string>Gen msg</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QComboBox" name="freeTextMsg">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>3</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>150</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Enter a free text message (maximum 13 characters)
or select a predefined macro from the dropdown list.
Press ENTER to add the current text to the predefined
list. The list can be maintained in Settings (F2).</string>
</property>
<property name="editable">
<bool>true</bool>
</property>
<property name="insertPolicy">
<enum>QComboBox::InsertAtBottom</enum>
</property>
</widget>
</item>
<item>
<widget class="QRadioButton" name="rbFreeText">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>1</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Send this free-text message (max 13 characters)</string>
</property>
<property name="text">
<string>Free msg</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<widget class="QWidget" name="tab_3">
<attribute name="title">
<string>3</string>
<string>2</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_11">
<item row="0" column="1" rowspan="2">
@ -2159,69 +1900,50 @@ list. The list can be maintained in Settings (F2).</string>
</widget>
</item>
<item>
<widget class="QSpinBox" name="sbTxPercent">
<property name="toolTip">
<string>Percentage of minute sequences devoted to transmitting.</string>
</property>
<property name="styleSheet">
<string notr="true">QSpinBox:enabled[notx=&quot;true&quot;] {
color: rgb(0, 0, 0);
background-color: rgb(255, 255, 0);
}</string>
</property>
<widget class="QSpinBox" name="sbFST4W_RxFreq">
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="suffix">
<string> %</string>
<string> Hz</string>
</property>
<property name="prefix">
<string>Tx Pct </string>
</property>
<property name="maximum">
<number>100</number>
</property>
</widget>
</item>
<item>
<widget class="RestrictedSpinBox" name="sbTR_FST4W">
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="suffix">
<string> s</string>
</property>
<property name="prefix">
<string>T/R </string>
<string>Rx </string>
</property>
<property name="minimum">
<number>15</number>
<number>100</number>
</property>
<property name="maximum">
<number>1800</number>
<number>4900</number>
</property>
<property name="singleStep">
<number>100</number>
</property>
<property name="value">
<number>1500</number>
</property>
</widget>
</item>
<item>
<widget class="QGroupBox" name="band_hopping_group_box">
<property name="title">
<string>Band Hopping</string>
<widget class="HintedSpinBox" name="sbFST4W_FTol">
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="checkable">
<bool>true</bool>
<property name="suffix">
<string> Hz</string>
</property>
<property name="prefix">
<string>F Tol </string>
</property>
<property name="minimum">
<number>100</number>
</property>
<property name="maximum">
<number>500</number>
</property>
<property name="singleStep">
<number>100</number>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_7">
<item>
<widget class="QPushButton" name="band_hopping_schedule_push_button">
<property name="toolTip">
<string>Choose bands and times of day for band-hopping.</string>
</property>
<property name="text">
<string>Schedule ...</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
@ -2339,6 +2061,72 @@ list. The list can be maintained in Settings (F2).</string>
</item>
</widget>
</item>
<item>
<widget class="QSpinBox" name="sbTxPercent">
<property name="toolTip">
<string>Percentage of minute sequences devoted to transmitting.</string>
</property>
<property name="styleSheet">
<string notr="true">QSpinBox:enabled[notx=&quot;true&quot;] {
color: rgb(0, 0, 0);
background-color: rgb(255, 255, 0);
}</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="suffix">
<string> %</string>
</property>
<property name="prefix">
<string>Tx Pct </string>
</property>
<property name="maximum">
<number>100</number>
</property>
</widget>
</item>
<item>
<widget class="RestrictedSpinBox" name="sbTR_FST4W">
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="suffix">
<string> s</string>
</property>
<property name="prefix">
<string>T/R </string>
</property>
<property name="minimum">
<number>15</number>
</property>
<property name="maximum">
<number>1800</number>
</property>
</widget>
</item>
<item>
<widget class="QGroupBox" name="band_hopping_group_box">
<property name="title">
<string>Band Hopping</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_7">
<item>
<widget class="QPushButton" name="band_hopping_schedule_push_button">
<property name="toolTip">
<string>Choose bands and times of day for band-hopping.</string>
</property>
<property name="text">
<string>Schedule ...</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item>
@ -2994,7 +2782,7 @@ Yellow when too low</string>
<addaction name="actionOnline_User_Guide"/>
<addaction name="actionLocal_User_Guide"/>
<addaction name="actionFT8_DXpedition_Mode_User_Guide"/>
<addaction name="actionQuick_Start_Guide_v2"/>
<addaction name="actionQuick_Start_Guide"/>
<addaction name="download_samples_action"/>
<addaction name="separator"/>
<addaction name="actionKeyboard_shortcuts"/>
@ -3065,17 +2853,6 @@ Yellow when too low</string>
<enum>QAction::QuitRole</enum>
</property>
</action>
<action name="actionDeviceSetup">
<property name="checkable">
<bool>false</bool>
</property>
<property name="text">
<string>Configuration</string>
</property>
<property name="shortcut">
<string>F2</string>
</property>
</action>
<action name="actionAbout">
<property name="text">
<string>About WSJT-X</string>
@ -3204,14 +2981,6 @@ Yellow when too low</string>
<string>Deep</string>
</property>
</action>
<action name="actionMonitor_OFF_at_startup">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Monitor OFF at startup</string>
</property>
</action>
<action name="actionErase_ALL_TXT">
<property name="text">
<string>Erase ALL.TXT</string>
@ -3222,97 +2991,6 @@ Yellow when too low</string>
<string>Erase wsjtx_log.adi</string>
</property>
</action>
<action name="actionConvert_JT9_x_to_RTTY">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Convert mode to RTTY for logging</string>
</property>
</action>
<action name="actionLog_dB_reports_to_Comments">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Log dB reports to Comments</string>
</property>
</action>
<action name="actionPrompt_to_log_QSO">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Prompt me to log QSO</string>
</property>
</action>
<action name="actionBlank_line_between_decoding_periods">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Blank line between decoding periods</string>
</property>
</action>
<action name="actionClear_DX_Call_and_Grid_after_logging">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Clear DX Call and Grid after logging</string>
</property>
</action>
<action name="actionDisplay_distance_in_miles">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Display distance in miles</string>
</property>
</action>
<action name="actionDouble_click_on_call_sets_Tx_Enable">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Double-click on call sets Tx Enable</string>
</property>
<property name="shortcut">
<string>F7</string>
</property>
</action>
<action name="action_73TxDisable">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Tx disabled after sending 73</string>
</property>
</action>
<action name="actionRunaway_Tx_watchdog">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Runaway Tx watchdog</string>
</property>
</action>
<action name="actionAllow_multiple_instances">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Allow multiple instances</string>
</property>
</action>
<action name="actionLockTxFreq">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Tx freq locked to Rx freq</string>
</property>
</action>
<action name="actionJT65">
<property name="checkable">
<bool>true</bool>
@ -3329,30 +3007,6 @@ Yellow when too low</string>
<string>JT9+JT65</string>
</property>
</action>
<action name="actionTx2QSO">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Tx messages to Rx Frequency window</string>
</property>
</action>
<action name="actionGray1">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Gray1</string>
</property>
</action>
<action name="actionEnable_DXCC_entity">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Show DXCC entity and worked B4 status</string>
</property>
</action>
<action name="actionAstronomical_data">
<property name="checkable">
<bool>true</bool>
@ -3595,19 +3249,14 @@ Yellow when too low</string>
<string>Color highlighting scheme</string>
</property>
</action>
<action name="actionContest_Log">
<property name="text">
<string>Contest Log</string>
</property>
</action>
<action name="actionExport_Cabrillo_log">
<property name="text">
<string>Export Cabrillo log ...</string>
</property>
</action>
<action name="actionQuick_Start_Guide_v2">
<action name="actionQuick_Start_Guide">
<property name="text">
<string>Quick-Start Guide to WSJT-X 2.0</string>
<string>Quick-Start Guide to FST4 and FST4W</string>
</property>
</action>
<action name="contest_log_action">
@ -3636,11 +3285,6 @@ Yellow when too low</string>
<string>FST4</string>
</property>
</action>
<action name="actionFT240W">
<property name="text">
<string>FT240W</string>
</property>
</action>
<action name="actionFST4W">
<property name="checkable">
<bool>true</bool>
@ -3649,25 +3293,6 @@ Yellow when too low</string>
<string>FST4W</string>
</property>
</action>
<action name="actionAlso_FST4W">
<property name="checkable">
<bool>true</bool>
</property>
<property name="enabled">
<bool>true</bool>
</property>
<property name="text">
<string>Also FST4W</string>
</property>
</action>
<action name="actionQRA66">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>QRA66</string>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<customwidgets>
@ -3736,16 +3361,6 @@ Yellow when too low</string>
<tabstop>sbSubmode</tabstop>
<tabstop>syncSpinBox</tabstop>
<tabstop>tabWidget</tabstop>
<tabstop>pbCallCQ</tabstop>
<tabstop>pbAnswerCQ</tabstop>
<tabstop>pbAnswerCaller</tabstop>
<tabstop>pbSendReport</tabstop>
<tabstop>pbSendRRR</tabstop>
<tabstop>pbSend73</tabstop>
<tabstop>genMsg</tabstop>
<tabstop>rbGenMsg</tabstop>
<tabstop>freeTextMsg</tabstop>
<tabstop>rbFreeText</tabstop>
<tabstop>outAttenuation</tabstop>
<tabstop>genStdMsgsPushButton</tabstop>
<tabstop>tx1</tabstop>

View File

@ -48,7 +48,8 @@ CPlotter::CPlotter(QWidget *parent) : //CPlotter Constructor
m_Percent2DScreen0 {0},
m_rxFreq {1020},
m_txFreq {0},
m_startFreq {0}
m_startFreq {0},
m_tol {100}
{
setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
setFocusPolicy(Qt::StrongFocus);
@ -495,8 +496,8 @@ void CPlotter::DrawOverlay() //DrawOverlay()
}
if(m_mode=="FST4W") {
x1=XfromFreq(2600);
x2=XfromFreq(2700);
x1=XfromFreq(m_rxFreq-m_tol);
x2=XfromFreq(m_rxFreq+m_tol);
painter0.drawLine(x1,26,x2,26);
}

View File

@ -55,6 +55,7 @@ include(widgets/widgets.pri)
include(Decoder/decodedtext.pri)
include(Detector/Detector.pri)
include(Modulator/Modulator.pri)
include(Audio/Audio.pri)
SOURCES += \
Radio.cpp NetworkServerLookup.cpp revision_utils.cpp \