Commit 1d9aa4cb authored by lm's avatar lm

Cleaned up minor things, small bugfixes

parent 6f445903
...@@ -65,7 +65,7 @@ macx { ...@@ -65,7 +65,7 @@ macx {
} }
} else { } else {
# x64 Mac OS X Snow Leopard 10.6 and later # x64 Mac OS X Snow Leopard 10.6 and later
CONFIG += x86_64 x86 cocoa CONFIG += x86_64 x86 cocoa phonon
#CONFIG -= x86 # phonon #CONFIG -= x86 # phonon
#message(Building for Mac OS X 64bit/Snow Leopard 10.6 and later) #message(Building for Mac OS X 64bit/Snow Leopard 10.6 and later)
debug { debug {
......
...@@ -295,11 +295,12 @@ void GAudioOutput::beep() ...@@ -295,11 +295,12 @@ void GAudioOutput::beep()
{ {
if (!muted) if (!muted)
{ {
// Use QFile to transform path for all OS // Use QFile to transform path for all OS
QFile f(QCoreApplication::applicationDirPath()+QString("/audio/alert.wav")); QFile f(QCoreApplication::applicationDirPath()+QString("/audio/alert.wav"));
m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str())); qDebug() << "FILE:" << f.fileName();
m_media->play(); m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str()));
} m_media->play();
}
} }
void GAudioOutput::selectFemaleVoice() void GAudioOutput::selectFemaleVoice()
......
...@@ -284,7 +284,7 @@ void MAVLinkSimulationWaypointPlanner::send_setpoint(uint16_t seq) ...@@ -284,7 +284,7 @@ void MAVLinkSimulationWaypointPlanner::send_setpoint(uint16_t seq)
PControlSetPoint.x = cur->x; PControlSetPoint.x = cur->x;
PControlSetPoint.y = cur->y; PControlSetPoint.y = cur->y;
PControlSetPoint.z = cur->z; PControlSetPoint.z = cur->z;
PControlSetPoint.yaw = cur->yaw; PControlSetPoint.yaw = cur->param4;
mavlink_msg_local_position_setpoint_set_encode(systemid, compid, &msg, &PControlSetPoint); mavlink_msg_local_position_setpoint_set_encode(systemid, compid, &msg, &PControlSetPoint);
link->sendMAVLinkMessage(&msg); link->sendMAVLinkMessage(&msg);
...@@ -299,7 +299,7 @@ void MAVLinkSimulationWaypointPlanner::send_setpoint(uint16_t seq) ...@@ -299,7 +299,7 @@ void MAVLinkSimulationWaypointPlanner::send_setpoint(uint16_t seq)
PControlSetPoint.x = cur->x; PControlSetPoint.x = cur->x;
PControlSetPoint.y = cur->y; PControlSetPoint.y = cur->y;
PControlSetPoint.z = cur->z; PControlSetPoint.z = cur->z;
PControlSetPoint.yaw = cur->yaw; PControlSetPoint.yaw = cur->param4;
mavlink_msg_local_position_setpoint_set_encode(systemid, compid, &msg, &PControlSetPoint); mavlink_msg_local_position_setpoint_set_encode(systemid, compid, &msg, &PControlSetPoint);
link->sendMAVLinkMessage(&msg); link->sendMAVLinkMessage(&msg);
...@@ -337,7 +337,7 @@ void MAVLinkSimulationWaypointPlanner::send_waypoint(uint8_t target_systemid, ui ...@@ -337,7 +337,7 @@ void MAVLinkSimulationWaypointPlanner::send_waypoint(uint8_t target_systemid, ui
wp->target_system = target_systemid; wp->target_system = target_systemid;
wp->target_component = target_compid; wp->target_component = target_compid;
if (verbose) qDebug("Sent waypoint %u (%u / %u / %u / %u / %u / %f / %u / %f / %f / %u / %f / %f / %f / %f / %u)\n", wp->seq, wp->target_system, wp->target_component, wp->seq, wp->frame, wp->action, wp->orbit, wp->orbit_direction, wp->param1, wp->param2, wp->current, wp->x, wp->y, wp->z, wp->yaw, wp->autocontinue); if (verbose) qDebug("Sent waypoint %u (%u / %u / %u / %u / %u / %f / %f / %f / %u / %f / %f / %f / %f / %u)\n", wp->seq, wp->target_system, wp->target_component, wp->seq, wp->frame, wp->action, wp->param3, wp->param1, wp->param2, wp->current, wp->x, wp->y, wp->z, wp->param4, wp->autocontinue);
mavlink_msg_waypoint_encode(systemid, compid, &msg, wp); mavlink_msg_waypoint_encode(systemid, compid, &msg, wp);
link->sendMAVLinkMessage(&msg); link->sendMAVLinkMessage(&msg);
...@@ -502,19 +502,19 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t* ...@@ -502,19 +502,19 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
//compare current yaw //compare current yaw
if (att.yaw - yaw_tolerance >= 0.0f && att.yaw + yaw_tolerance < 2.f*M_PI) if (att.yaw - yaw_tolerance >= 0.0f && att.yaw + yaw_tolerance < 2.f*M_PI)
{ {
if (att.yaw - yaw_tolerance <= wp->yaw && att.yaw + yaw_tolerance >= wp->yaw) if (att.yaw - yaw_tolerance <= wp->param4 && att.yaw + yaw_tolerance >= wp->param4)
yawReached = true; yawReached = true;
} }
else if(att.yaw - yaw_tolerance < 0.0f) else if(att.yaw - yaw_tolerance < 0.0f)
{ {
float lowerBound = 360.0f + att.yaw - yaw_tolerance; float lowerBound = 360.0f + att.yaw - yaw_tolerance;
if (lowerBound < wp->yaw || wp->yaw < att.yaw + yaw_tolerance) if (lowerBound < wp->param4 || wp->param4 < att.yaw + yaw_tolerance)
yawReached = true; yawReached = true;
} }
else else
{ {
float upperBound = att.yaw + yaw_tolerance - 2.f*M_PI; float upperBound = att.yaw + yaw_tolerance - 2.f*M_PI;
if (att.yaw - yaw_tolerance < wp->yaw || wp->yaw < upperBound) if (att.yaw - yaw_tolerance < wp->param4 || wp->param4 < upperBound)
yawReached = true; yawReached = true;
} }
......
/*===================================================================== /*=====================================================================
QGroundControl Open Source Ground Control Station QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> (c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
...@@ -10,15 +9,15 @@ This file is part of the QGROUNDCONTROL project ...@@ -10,15 +9,15 @@ This file is part of the QGROUNDCONTROL project
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or
(at your option) any later version. (at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful, QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details. GNU General Public License for more details.
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/ ======================================================================*/
#include "PxQuadMAV.h" #include "PxQuadMAV.h"
...@@ -39,20 +38,12 @@ PxQuadMAV::PxQuadMAV(MAVLinkProtocol* mavlink, int id) : ...@@ -39,20 +38,12 @@ PxQuadMAV::PxQuadMAV(MAVLinkProtocol* mavlink, int id) :
*/ */
void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{ {
// Let UAS handle the default message set // Only compile this portion if matching MAVLink packets have been compiled
UAS::receiveMessage(link, message);
//qDebug() << "PX RECEIVED" << msg->sysid << msg->compid << msg->msgid;
// Only compile this portion if matching MAVLink packets have been compiled
#ifdef MAVLINK_ENABLED_PIXHAWK #ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t* msg = &message; mavlink_message_t* msg = &message;
if (message.sysid == uasId) if (message.sysid == uasId)
{ {
// QString uasState;
// QString stateDescription;
// QString patternPath;
switch (message.msgid) switch (message.msgid)
{ {
case MAVLINK_MSG_ID_RAW_AUX: case MAVLINK_MSG_ID_RAW_AUX:
...@@ -88,7 +79,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -88,7 +79,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit letterDetected(uasId, name, detected.confidence, detected.detected); emit letterDetected(uasId, name, detected.confidence, detected.detected);
} }
break; break;
case MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT: case MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT:
{ {
mavlink_watchdog_heartbeat_t payload; mavlink_watchdog_heartbeat_t payload;
mavlink_msg_watchdog_heartbeat_decode(msg, &payload); mavlink_msg_watchdog_heartbeat_decode(msg, &payload);
...@@ -97,7 +88,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -97,7 +88,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
break; break;
case MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO: case MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO:
{ {
mavlink_watchdog_process_info_t payload; mavlink_watchdog_process_info_t payload;
mavlink_msg_watchdog_process_info_decode(msg, &payload); mavlink_msg_watchdog_process_info_decode(msg, &payload);
...@@ -106,14 +97,14 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -106,14 +97,14 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
break; break;
case MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS: case MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS:
{ {
mavlink_watchdog_process_status_t payload; mavlink_watchdog_process_status_t payload;
mavlink_msg_watchdog_process_status_decode(msg, &payload); mavlink_msg_watchdog_process_status_decode(msg, &payload);
emit processChanged(this->uasId, payload.watchdog_id, payload.process_id, payload.state, (payload.muted == 1) ? true : false, payload.crashes, payload.pid); emit processChanged(this->uasId, payload.watchdog_id, payload.process_id, payload.state, (payload.muted == 1) ? true : false, payload.crashes, payload.pid);
} }
break; break;
case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE: case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
{ {
mavlink_vision_position_estimate_t pos; mavlink_vision_position_estimate_t pos;
mavlink_msg_vision_position_estimate_decode(&message, &pos); mavlink_msg_vision_position_estimate_decode(&message, &pos);
...@@ -128,21 +119,21 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -128,21 +119,21 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
break; break;
case MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE: case MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE:
{ {
mavlink_vicon_position_estimate_t pos; mavlink_vicon_position_estimate_t pos;
mavlink_msg_vicon_position_estimate_decode(&message, &pos); mavlink_msg_vicon_position_estimate_decode(&message, &pos);
quint64 time = getUnixTime(pos.usec); quint64 time = getUnixTime(pos.usec);
//emit valueChanged(uasId, "vis. time", pos.usec, time); //emit valueChanged(uasId, "vis. time", pos.usec, time);
emit valueChanged(uasId, "vicon roll", "rad", pos.roll, time); emit valueChanged(uasId, "vicon roll", "rad", pos.roll, time);
emit valueChanged(uasId, "vicon pitch", "rad", pos.pitch, time); emit valueChanged(uasId, "vicon pitch", "rad", pos.pitch, time);
emit valueChanged(uasId, "vicon yaw", "rad", pos.yaw, time); emit valueChanged(uasId, "vicon yaw", "rad", pos.yaw, time);
emit valueChanged(uasId, "vicon x", "m", pos.x, time); emit valueChanged(uasId, "vicon x", "m", pos.x, time);
emit valueChanged(uasId, "vicon y", "m", pos.y, time); emit valueChanged(uasId, "vicon y", "m", pos.y, time);
emit valueChanged(uasId, "vicon z", "m", pos.z, time); emit valueChanged(uasId, "vicon z", "m", pos.z, time);
emit localPositionChanged(this, pos.x, pos.y, pos.z, time); emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
} }
break; break;
case MAVLINK_MSG_ID_AUX_STATUS: case MAVLINK_MSG_ID_AUX_STATUS:
{ {
mavlink_aux_status_t status; mavlink_aux_status_t status;
mavlink_msg_aux_status_decode(&message, &status); mavlink_msg_aux_status_decode(&message, &status);
...@@ -155,8 +146,9 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -155,8 +146,9 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "Load", "%", ((float)status.load)/1000.0f, MG::TIME::getGroundTimeNow()); emit valueChanged(uasId, "Load", "%", ((float)status.load)/1000.0f, MG::TIME::getGroundTimeNow());
} }
break; break;
default: default:
// Do nothing // Let UAS handle the default message set
UAS::receiveMessage(link, message);
break; break;
} }
} }
......
...@@ -192,9 +192,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -192,9 +192,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
QString uasState; QString uasState;
QString stateDescription; QString stateDescription;
// Receive named value message
receiveMessageNamedValue(message);
switch (message.msgid) switch (message.msgid)
{ {
case MAVLINK_MSG_ID_HEARTBEAT: case MAVLINK_MSG_ID_HEARTBEAT:
...@@ -223,6 +220,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -223,6 +220,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit systemTypeSet(this, type); emit systemTypeSet(this, type);
} }
break;
case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
case MAVLINK_MSG_ID_NAMED_VALUE_INT:
// Receive named value message
receiveMessageNamedValue(message);
break; break;
case MAVLINK_MSG_ID_BOOT: case MAVLINK_MSG_ID_BOOT:
getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription); getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription);
...@@ -237,7 +239,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -237,7 +239,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// FIXME // FIXME
//qDebug() << "SYSTEM NAV MODE:" << state.nav_mode; //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
QString audiostring = "System " + QString::number(this->getUASID()); QString audiostring = "System " + getUASName();
QString stateAudio = ""; QString stateAudio = "";
QString modeAudio = ""; QString modeAudio = "";
bool statechanged = false; bool statechanged = false;
...@@ -277,7 +279,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -277,7 +279,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mode = "GUIDED MODE"; mode = "GUIDED MODE";
break; break;
case (uint8_t)MAV_MODE_READY: case (uint8_t)MAV_MODE_READY:
mode = "READY"; mode = "READY MODE";
break; break;
case (uint8_t)MAV_MODE_TEST1: case (uint8_t)MAV_MODE_TEST1:
mode = "TEST1 MODE"; mode = "TEST1 MODE";
...@@ -748,6 +750,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -748,6 +750,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_waypoint_reached_t wpr; mavlink_waypoint_reached_t wpr;
mavlink_msg_waypoint_reached_decode(&message, &wpr); mavlink_msg_waypoint_reached_decode(&message, &wpr);
waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr); waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
GAudioOutput::instance()->say(QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq));
} }
break; break;
...@@ -866,12 +869,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -866,12 +869,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
break; break;
#endif #endif
// Messages to ignore
case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET:
break;
default: default:
{ {
if (!unknownPackets.contains(message.msgid)) if (!unknownPackets.contains(message.msgid))
{ {
unknownPackets.append(message.msgid); unknownPackets.append(message.msgid);
QString errString = tr("UNABLE TO DECODE MESSAGE WITH ID %1").arg(message.msgid); QString errString = tr("UNABLE TO DECODE MESSAGE NUMBER %1").arg(message.msgid);
GAudioOutput::instance()->say(errString+tr(", please check the communication console for details.")); GAudioOutput::instance()->say(errString+tr(", please check the communication console for details."));
emit textMessageReceived(uasId, message.compid, 255, errString); emit textMessageReceived(uasId, message.compid, 255, errString);
std::cout << "Unable to decode message from system " << std::dec << static_cast<int>(message.sysid) << " with message id:" << static_cast<int>(message.msgid) << std::endl; std::cout << "Unable to decode message from system " << std::dec << static_cast<int>(message.sysid) << " with message id:" << static_cast<int>(message.msgid) << std::endl;
...@@ -1928,7 +1934,7 @@ void UAS::startLowBattAlarm() ...@@ -1928,7 +1934,7 @@ void UAS::startLowBattAlarm()
{ {
if (!lowBattAlarm) if (!lowBattAlarm)
{ {
GAudioOutput::instance()->alert("LOW BATTERY"); GAudioOutput::instance()->alert(tr("SYSTEM %1 HAS LOW BATTERY").arg(getUASName()));
QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency())); QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lowBattAlarm = true; lowBattAlarm = true;
} }
......
...@@ -138,8 +138,8 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_ ...@@ -138,8 +138,8 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
if(wp->seq == current_wp_id) if(wp->seq == current_wp_id)
{ {
qDebug() << "Got WP: " << wp->seq << wp->x << wp->y << wp->z << wp->yaw << "auto:" << wp->autocontinue << "curr:" << wp->current << wp->param1 << wp->param2 << (MAV_FRAME) wp->frame << (MAV_ACTION) wp->action; qDebug() << "Got WP: " << wp->seq << wp->x << wp->y << wp->z << wp->param4 << "auto:" << wp->autocontinue << "curr:" << wp->current << wp->param1 << wp->param2 << (MAV_FRAME) wp->frame << (MAV_ACTION) wp->action;
Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->yaw, wp->autocontinue, wp->current, wp->param1, wp->param2, (MAV_FRAME) wp->frame, (MAV_ACTION) wp->action); Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param4, wp->autocontinue, wp->current, wp->param1, wp->param2, (MAV_FRAME) wp->frame, (MAV_ACTION) wp->action);
addWaypoint(lwp, false); addWaypoint(lwp, false);
//get next waypoint //get next waypoint
...@@ -663,8 +663,7 @@ void UASWaypointManager::writeWaypoints() ...@@ -663,8 +663,7 @@ void UASWaypointManager::writeWaypoints()
cur_d->autocontinue = cur_s->getAutoContinue(); cur_d->autocontinue = cur_s->getAutoContinue();
cur_d->current = cur_s->getCurrent() & noCurrent; //make sure only one current waypoint is selected, the first selected will be chosen cur_d->current = cur_s->getCurrent() & noCurrent; //make sure only one current waypoint is selected, the first selected will be chosen
cur_d->orbit = cur_s->getLoiterOrbit(); cur_d->param3 = cur_s->getLoiterOrbit();
cur_d->orbit_direction = 0;
cur_d->param1 = cur_s->getParam1(); cur_d->param1 = cur_s->getParam1();
cur_d->param2 = cur_s->getParam2(); cur_d->param2 = cur_s->getParam2();
cur_d->frame = cur_s->getFrame(); cur_d->frame = cur_s->getFrame();
...@@ -673,7 +672,7 @@ void UASWaypointManager::writeWaypoints() ...@@ -673,7 +672,7 @@ void UASWaypointManager::writeWaypoints()
cur_d->x = cur_s->getX(); cur_d->x = cur_s->getX();
cur_d->y = cur_s->getY(); cur_d->y = cur_s->getY();
cur_d->z = cur_s->getZ(); cur_d->z = cur_s->getZ();
cur_d->yaw = cur_s->getYaw(); cur_d->param4 = cur_s->getYaw();
if (cur_s->getCurrent() && noCurrent) if (cur_s->getCurrent() && noCurrent)
noCurrent = false; noCurrent = false;
......
...@@ -6,7 +6,7 @@ ...@@ -6,7 +6,7 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>237</width> <width>307</width>
<height>221</height> <height>221</height>
</rect> </rect>
</property> </property>
...@@ -134,7 +134,7 @@ ...@@ -134,7 +134,7 @@
<item row="1" column="1"> <item row="1" column="1">
<widget class="QLabel" name="label_2"> <widget class="QLabel" name="label_2">
<property name="text"> <property name="text">
<string>Extended</string> <string>Ext. Status</string>
</property> </property>
</widget> </widget>
</item> </item>
...@@ -148,7 +148,7 @@ ...@@ -148,7 +148,7 @@
<item row="5" column="1"> <item row="5" column="1">
<widget class="QLabel" name="label_4"> <widget class="QLabel" name="label_4">
<property name="text"> <property name="text">
<string>Controller</string> <string>Raw Contr.</string>
</property> </property>
</widget> </widget>
</item> </item>
...@@ -183,7 +183,7 @@ ...@@ -183,7 +183,7 @@
<item row="0" column="3"> <item row="0" column="3">
<widget class="QLabel" name="label_5"> <widget class="QLabel" name="label_5">
<property name="text"> <property name="text">
<string>RC Values</string> <string>RC Chan.</string>
</property> </property>
</widget> </widget>
</item> </item>
......
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