Commit 24201265 authored by James Goppert's avatar James Goppert

Split scaled and raw rc packets to match mavlink

parent d99fa330
......@@ -424,7 +424,7 @@ void MAVLinkSimulationLink::mainloop()
static int rcCounter = 0;
if (rcCounter == 2)
{
mavlink_rc_channels_t chan;
mavlink_rc_channels_raw_t chan;
chan.chan1_raw = 1000 + ((int)(fabs(x) * 1000) % 2000);
chan.chan2_raw = 1000 + ((int)(fabs(y) * 1000) % 2000);
chan.chan3_raw = 1000 + ((int)(fabs(z) * 1000) % 2000);
......@@ -433,15 +433,7 @@ void MAVLinkSimulationLink::mainloop()
chan.chan6_raw = (chan.chan3_raw + chan.chan2_raw) / 2.0f;
chan.chan7_raw = (chan.chan4_raw + chan.chan2_raw) / 2.0f;
chan.chan8_raw = (chan.chan6_raw + chan.chan2_raw) / 2.0f;
chan.chan1_255 = ((chan.chan1_raw - 1000)/1000.0f) * 255.0f;
chan.chan2_255 = ((chan.chan2_raw - 1000)/1000.0f) * 255.0f;
chan.chan3_255 = ((chan.chan3_raw - 1000)/1000.0f) * 255.0f;
chan.chan4_255 = ((chan.chan4_raw - 1000)/1000.0f) * 255.0f;
chan.chan5_255 = ((chan.chan5_raw - 1000)/1000.0f) * 255.0f;
chan.chan6_255 = ((chan.chan6_raw - 1000)/1000.0f) * 255.0f;
chan.chan7_255 = ((chan.chan7_raw - 1000)/1000.0f) * 255.0f;
chan.chan8_255 = ((chan.chan8_raw - 1000)/1000.0f) * 255.0f;
messageSize = mavlink_msg_rc_channels_encode(systemId, componentId, &msg, &chan);
messageSize = mavlink_msg_rc_channels_raw_encode(systemId, componentId, &msg, &chan);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......
......@@ -323,7 +323,7 @@ void OpalLink::getSignals()
if (sendRCValues)
{
mavlink_message_t rc;
mavlink_msg_rc_channels_pack(systemID, componentID, &rc,
mavlink_msg_rc_channels_raw_pack(systemID, componentID, &rc,
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_1]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_2]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_3]),
......@@ -332,14 +332,6 @@ void OpalLink::getSignals()
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_6]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_7]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_8]),
rescaleNorm(values[OpalRT::NORM_CHANNEL_1], OpalRT::NORM_CHANNEL_1),
rescaleNorm(values[OpalRT::NORM_CHANNEL_2], OpalRT::NORM_CHANNEL_2),
rescaleNorm(values[OpalRT::NORM_CHANNEL_3], OpalRT::NORM_CHANNEL_3),
rescaleNorm(values[OpalRT::NORM_CHANNEL_4], OpalRT::NORM_CHANNEL_4),
rescaleNorm(values[OpalRT::NORM_CHANNEL_5], OpalRT::NORM_CHANNEL_5),
rescaleNorm(values[OpalRT::NORM_CHANNEL_6], OpalRT::NORM_CHANNEL_6),
rescaleNorm(values[OpalRT::NORM_CHANNEL_7], OpalRT::NORM_CHANNEL_7),
rescaleNorm(values[OpalRT::NORM_CHANNEL_8], OpalRT::NORM_CHANNEL_8),
0 //rssi unused
);
receiveMessage(rc);
......
......@@ -407,41 +407,34 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
}
break;
case MAVLINK_MSG_ID_RC_CHANNELS:
case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
{
mavlink_rc_channels_t channels;
mavlink_msg_rc_channels_decode(&message, &channels);
mavlink_rc_channels_raw_t channels;
mavlink_msg_rc_channels_raw_decode(&message, &channels);
emit remoteControlRSSIChanged(channels.rssi/255.0f);
for (int i = 0; i < 8; i++)
{
switch (i)
{
case 0:
emit remoteControlChannelChanged(i, channels.chan1_raw, channels.chan1_255/255.0f);
break;
case 1:
emit remoteControlChannelChanged(i, channels.chan2_raw, channels.chan2_255/255.0f);
break;
case 2:
emit remoteControlChannelChanged(i, channels.chan3_raw, channels.chan3_255/255.0f);
break;
case 3:
emit remoteControlChannelChanged(i, channels.chan4_raw, channels.chan4_255/255.0f);
break;
case 4:
emit remoteControlChannelChanged(i, channels.chan5_raw, channels.chan5_255/255.0f);
break;
case 5:
emit remoteControlChannelChanged(i, channels.chan6_raw, channels.chan6_255/255.0f);
break;
case 6:
emit remoteControlChannelChanged(i, channels.chan7_raw, channels.chan7_255/255.0f);
break;
case 7:
emit remoteControlChannelChanged(i, channels.chan8_raw, channels.chan8_255/255.0f);
break;
}
}
emit remoteControlChannelRawChanged(0, channels.chan1_raw);
emit remoteControlChannelRawChanged(1, channels.chan2_raw);
emit remoteControlChannelRawChanged(2, channels.chan3_raw);
emit remoteControlChannelRawChanged(3, channels.chan4_raw);
emit remoteControlChannelRawChanged(4, channels.chan5_raw);
emit remoteControlChannelRawChanged(5, channels.chan6_raw);
emit remoteControlChannelRawChanged(6, channels.chan7_raw);
emit remoteControlChannelRawChanged(7, channels.chan8_raw);
}
break;
case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
{
mavlink_rc_channels_scaled_t channels;
mavlink_msg_rc_channels_scaled_decode(&message, &channels);
emit remoteControlRSSIChanged(channels.rssi/255.0f);
emit remoteControlChannelScaledChanged(0, channels.chan1_scaled/10000.0f);
emit remoteControlChannelScaledChanged(1, channels.chan2_scaled/10000.0f);
emit remoteControlChannelScaledChanged(2, channels.chan3_scaled/10000.0f);
emit remoteControlChannelScaledChanged(3, channels.chan4_scaled/10000.0f);
emit remoteControlChannelScaledChanged(4, channels.chan5_scaled/10000.0f);
emit remoteControlChannelScaledChanged(5, channels.chan6_scaled/10000.0f);
emit remoteControlChannelScaledChanged(6, channels.chan7_scaled/10000.0f);
emit remoteControlChannelScaledChanged(7, channels.chan8_scaled/10000.0f);
}
break;
case MAVLINK_MSG_ID_PARAM_VALUE:
......
......@@ -356,8 +356,10 @@ signals:
void positionZControlEnabled(bool enabled);
/** @brief Heading control enabled/disabled */
void positionYawControlEnabled(bool enabled);
/** @brief Value of a remote control channel */
void remoteControlChannelChanged(int channelId, float raw, float normalized);
/** @brief Value of a remote control channel (raw) */
void remoteControlChannelRawChanged(int channelId, float raw);
/** @brief Value of a remote control channel (scaled)*/
void remoteControlChannelScaledChanged(int channelId, float normalized);
/** @brief Remote control RSSI changed */
void remoteControlRSSIChanged(float rssi);
/** @brief Radio Calibration Data has been received from the MAV*/
......
......@@ -96,10 +96,11 @@ void QGCRemoteControlView::setUASId(int id)
if (uas)
{
// The UAS exists, disconnect any existing connections
disconnect(uas, SIGNAL(remoteControlChannelChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
disconnect(uas, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
disconnect(uas, SIGNAL(radioCalibrationReceived(const QPointer<RadioCalibrationData>)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
disconnect(uas, SIGNAL(remoteControlChannelChanged(int,float,float)), calibrationWindow, SLOT(setChannel(int,float,float)));
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
disconnect(uas, SIGNAL(remoteControlRSSIRawChanged(float)), this, SLOT(setRemoteRSSI(float)));
disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer<RadioCalibrationData>)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
disconnect(uas, SIGNAL(remoteControlChannelScaledChanged(int,float,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
}
}
......@@ -111,25 +112,49 @@ void QGCRemoteControlView::setUASId(int id)
nameLabel->setText(QString("RC Input of %1").arg(newUAS->getUASName()));
calibrationWindow->setUASId(id);
connect(newUAS, SIGNAL(radioCalibrationReceived(const QPointer<RadioCalibrationData>&)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
connect(newUAS, SIGNAL(remoteControlChannelChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
connect(newUAS, SIGNAL(remoteControlChannelChanged(int,float,float)), calibrationWindow, SLOT(setChannel(int,float,float)));
connect(newUAS, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(setChannelRaw(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
}
}
void QGCRemoteControlView::setChannel(int channelId, float raw, float normalized)
void QGCRemoteControlView::setChannelRaw(int channelId, float raw)
{
if (this->raw.size() <= channelId)
{
// This is a new channel, append it
this->raw.append(raw);
this->normalized.append(0);
appendChannelWidget(channelId);
}
else
{
// This is an existing channel, aupdate it
this->raw[channelId] = raw;
}
updated = true;
// FIXME Will be timer based in the future
redraw();
}
void QGCRemoteControlView::setChannelScaled(int channelId, float normalized)
{
if (this->raw.size() <= channelId) // using raw vector as size indicator
{
// This is a new channel, append it
this->normalized.append(normalized);
this->raw.append(0);
appendChannelWidget(channelId);
}
else
{
// This is an existing channel, update it
this->raw[channelId] = raw;
this->normalized[channelId] = normalized;
}
updated = true;
......@@ -156,8 +181,9 @@ void QGCRemoteControlView::appendChannelWidget(int channelId)
layout->addWidget(raw);
// Append progress bar
QProgressBar* normalized = new QProgressBar(this);
normalized->setMinimum(0);
normalized->setMinimum(-100);
normalized->setMaximum(100);
normalized->setFormat("%v%");
progressBars.append(normalized);
layout->addWidget(normalized);
channelLayout->addLayout(layout);
......
......@@ -52,7 +52,8 @@ public:
public slots:
void setUASId(int id);
void setChannel(int channelId, float raw, float normalized);
void setChannelRaw(int channelId, float raw);
void setChannelScaled(int channelId, float normalized);
void setRemoteRSSI(float rssiNormalized);
void redraw();
......
......@@ -165,8 +165,20 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="textVisible">
<bool>true</bool>
</property>
<property name="invertedAppearance">
<bool>false</bool>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan2ProgressBar">
......@@ -178,8 +190,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan3ProgressBar">
......@@ -191,8 +209,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan4ProgressBar">
......@@ -204,8 +228,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan5ProgressBar">
......@@ -217,8 +247,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan6ProgressBar">
......@@ -230,8 +266,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan7ProgressBar">
......@@ -243,8 +285,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan8ProgressBar">
......@@ -256,8 +304,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QLabel" name="label_11">
......
......@@ -122,7 +122,7 @@ void WaypointList::setUAS(UASInterface* uas)
{
this->uas = uas;
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updatePosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
connect(&uas->getWaypointManager(), SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &)));
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment