diff --git a/QGCExternalLibs.pri b/QGCExternalLibs.pri index 606ca5947fb9744c36d766c70c693bbb12cc7dd8..8b7edd40fe3e9ce5fbb5a606d2bbe0f133870be5 100644 --- a/QGCExternalLibs.pri +++ b/QGCExternalLibs.pri @@ -31,12 +31,6 @@ else:exists(user_config.pri):infile(user_config.pri, MAVLINK_CONF) { message($$sprintf("Using MAVLink dialect '%1' specified in user_config.pri", $$MAVLINK_CONF)) } } -# If no valid user selection is found, default to the pixhawk if it's available. -# Note: This can be a list of several dialects. -else { - MAVLINK_CONF=pixhawk - message($$sprintf("Using default MAVLink dialect '%1'.", $$MAVLINK_CONF)) -} # Then we add the proper include paths dependent on the dialect. INCLUDEPATH += $$MAVLINKPATH diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 0c0b7088e623a341c164d3efed2af28583c471cf..3d267ecb827b38e00599aee4c05854b4777ae3b3 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -243,7 +243,6 @@ INCLUDEPATH += \ src/lib/qmapcontrol \ src/ui/mavlink \ src/ui/param \ - src/ui/watchdog \ src/ui/map3D \ src/ui/mission \ src/ui/designer \ @@ -262,16 +261,12 @@ FORMS += \ src/ui/UASView.ui \ src/ui/ParameterInterface.ui \ src/ui/WaypointList.ui \ - src/ui/ObjectDetectionView.ui \ src/ui/JoystickWidget.ui \ src/ui/DebugConsole.ui \ src/ui/HDDisplay.ui \ src/ui/MAVLinkSettingsWidget.ui \ src/ui/AudioOutputWidget.ui \ src/ui/QGCSensorSettingsWidget.ui \ - src/ui/watchdog/WatchdogControl.ui \ - src/ui/watchdog/WatchdogProcessView.ui \ - src/ui/watchdog/WatchdogView.ui \ src/ui/QGCDataPlot2D.ui \ src/ui/QGCRemoteControlView.ui \ src/ui/QMap3D.ui \ @@ -370,7 +365,6 @@ HEADERS += \ src/ui/ParameterInterface.h \ src/ui/WaypointList.h \ src/Waypoint.h \ - src/ui/ObjectDetectionView.h \ src/input/JoystickInput.h \ src/ui/JoystickWidget.h \ src/ui/DebugConsole.h \ @@ -382,10 +376,6 @@ HEADERS += \ src/ui/QGCParamWidget.h \ src/ui/QGCSensorSettingsWidget.h \ src/ui/linechart/Linecharts.h \ - src/uas/PxQuadMAV.h \ - src/ui/watchdog/WatchdogControl.h \ - src/ui/watchdog/WatchdogProcessView.h \ - src/ui/watchdog/WatchdogView.h \ src/uas/UASWaypointManager.h \ src/ui/HSIDisplay.h \ src/QGC.h \ @@ -528,7 +518,6 @@ SOURCES += \ src/ui/ParameterInterface.cc \ src/ui/WaypointList.cc \ src/Waypoint.cc \ - src/ui/ObjectDetectionView.cc \ src/input/JoystickInput.cc \ src/ui/JoystickWidget.cc \ src/ui/DebugConsole.cc \ @@ -540,10 +529,6 @@ SOURCES += \ src/ui/QGCParamWidget.cc \ src/ui/QGCSensorSettingsWidget.cc \ src/ui/linechart/Linecharts.cc \ - src/uas/PxQuadMAV.cc \ - src/ui/watchdog/WatchdogControl.cc \ - src/ui/watchdog/WatchdogProcessView.cc \ - src/ui/watchdog/WatchdogView.cc \ src/uas/UASWaypointManager.cc \ src/ui/HSIDisplay.cc \ src/QGC.cc \ diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 4985d90463febdbe8ef7a885f764be514a7c2b87..37b85f6cc5e28834503e9ee2b68cc59ca7b49c0e 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -24,7 +24,6 @@ #include "UASManager.h" #include "UASInterface.h" #include "UAS.h" -#include "PxQuadMAV.h" #include "configuration.h" #include "LinkManager.h" #include "QGCMAVLink.h" diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 1bced51fc31fcebce5fc1aacf1024d20bfaa01cd..44e53f1395d1617a924a8f6180856530b4f928b1 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -197,10 +197,6 @@ void MAVLinkSimulationLink::mainloop() mavlink_attitude_t attitude; memset(&attitude, 0, sizeof(mavlink_attitude_t)); -#ifdef MAVLINK_ENABLED_PIXHAWK - mavlink_raw_aux_t rawAuxValues; - memset(&rawAuxValues, 0, sizeof(mavlink_raw_aux_t)); -#endif mavlink_raw_imu_t rawImuValues; memset(&rawImuValues, 0, sizeof(mavlink_raw_imu_t)); @@ -301,15 +297,6 @@ void MAVLinkSimulationLink::mainloop() rawImuValues.zgyro = d; attitude.yawspeed = ((d-29.000)/3000.0)*2.7-2.7-2.65; } -#ifdef MAVLINK_ENABLED_PIXHAWK - if (keys.value(i, "") == "Pressure") { - rawAuxValues.baro = d; - } - - if (keys.value(i, "") == "Battery") { - rawAuxValues.vbat = d; - } -#endif if (keys.value(i, "") == "roll_IMU") { attitude.roll = d; } @@ -473,46 +460,6 @@ void MAVLinkSimulationLink::mainloop() static int detectionCounter = 6; if (detectionCounter % 10 == 0) { -#ifdef MAVLINK_ENABLED_PIXHAWK - mavlink_pattern_detected_t detected; - detected.confidence = 5.0f; - detected.type = 0; // compiler confused into thinking type is used unitialized, bogus init to silence - - if (detectionCounter == 10) { - char fileName[] = "patterns/face5.png"; - memcpy(detected.file, fileName, sizeof(fileName)); - detected.type = 0; // 0: Pattern, 1: Letter - } else if (detectionCounter == 20) { - char fileName[] = "7"; - memcpy(detected.file, fileName, sizeof(fileName)); - detected.type = 1; // 0: Pattern, 1: Letter - } else if (detectionCounter == 30) { - char fileName[] = "patterns/einstein.bmp"; - memcpy(detected.file, fileName, sizeof(fileName)); - detected.type = 0; // 0: Pattern, 1: Letter - } else if (detectionCounter == 40) { - char fileName[] = "F"; - memcpy(detected.file, fileName, sizeof(fileName)); - detected.type = 1; // 0: Pattern, 1: Letter - } else if (detectionCounter == 50) { - char fileName[] = "patterns/face2.png"; - memcpy(detected.file, fileName, sizeof(fileName)); - detected.type = 0; // 0: Pattern, 1: Letter - } else if (detectionCounter == 60) { - char fileName[] = "H"; - memcpy(detected.file, fileName, sizeof(fileName)); - detected.type = 1; // 0: Pattern, 1: Letter - detectionCounter = 0; - } - detected.detected = 1; - mavlink_msg_pattern_detected_encode(systemId, componentId, &msg, &detected); - // Allocate buffer with packet data - bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); - //add data into datastream - memcpy(stream+streampointer,buffer, bufferlength); - streampointer += bufferlength; - //detectionCounter = 0; -#endif } detectionCounter++; @@ -701,14 +648,6 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) // } } break; -#ifdef MAVLINK_ENABLED_PIXHAWK - case MAVLINK_MSG_ID_MANUAL_CONTROL: { - mavlink_manual_control_t control; - mavlink_msg_manual_control_decode(&msg, &control); -// qDebug() << "\n" << "ROLL:" << control.x << "PITCH:" << control.y; - } - break; -#endif case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { // qDebug() << "GCS REQUESTED PARAM LIST FROM SIMULATION"; diff --git a/src/comm/OpalLink.cc b/src/comm/OpalLink.cc index 7a1d5ed7ea0538fe6fddbeb9c361a657c6d75895..6295d837d20415186896a407e1992e020ea71201 100644 --- a/src/comm/OpalLink.cc +++ b/src/comm/OpalLink.cc @@ -199,47 +199,6 @@ void OpalLink::writeBytes(const char *bytes, qint64 length) params->getParameter(OpalRT::SERVO_INPUTS, "PIT_SET4_IN").setValue(((radio.pitch[4]>900 /*in us?*/)?radio.pitch[4]/1000:radio.pitch[4])); } break; -#endif -#ifdef MAVLINK_ENABLED_PIXHAWK - case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: { - mavlink_request_data_stream_t stream; - mavlink_msg_request_data_stream_decode(&msg, &stream); - switch (stream.req_stream_id) { - case 0: // All data types - break; - case 1: // Raw Sensor Data - break; - case 2: // extended system status - break; - case 3: // rc channel data - sendRCValues = (stream.start_stop == 1?true:false); - break; - case 4: // raw controller - if (stream.start_stop == 1) - sendRawController = true; - else - sendRawController = false; - break; - case 5: // raw sensor fusion - break; - case 6: // position - sendPosition = (stream.start_stop == 1?true:false); - break; - case 7: // extra 1 - break; - case 8: // extra 2 - break; - case 9: // extra 3 - break; - default: - qDebug() << __FILE__ << __LINE__ << "Received Unknown Data Strem Request with ID" << stream.req_stream_id; - } - } - break; - default: { - qDebug() << "OpalLink::writeBytes(): Unknown mavlink packet"; - } - } #endif } diff --git a/src/comm/QGCMAVLink.h b/src/comm/QGCMAVLink.h index b9808ddaf5dadbb6a0592a02c7cf1e0575bbbae5..816da3ab6ddc5004bc0b63a22ee81d96009d449f 100644 --- a/src/comm/QGCMAVLink.h +++ b/src/comm/QGCMAVLink.h @@ -32,12 +32,5 @@ This file is part of the QGROUNDCONTROL project #include -//#ifdef MAVLINK_CONF -//#define MY_MACRO(x) -//#include MY_MACRO(MAVLINK_CONF) -//#include MAVLINK_CONF -//#endif - - #endif // QGCMAVLINK_H diff --git a/src/uas/PxQuadMAV.cc b/src/uas/PxQuadMAV.cc deleted file mode 100644 index d7fbb8cef1033c5bfff9324abc012d58c2e1b3e3..0000000000000000000000000000000000000000 --- a/src/uas/PxQuadMAV.cc +++ /dev/null @@ -1,226 +0,0 @@ -/*===================================================================== -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -#include "PxQuadMAV.h" -#include "GAudioOutput.h" - -PxQuadMAV::PxQuadMAV(MAVLinkProtocol* mavlink, QThread* thread, int id) : - UAS(mavlink, thread, id) -{ -} - -/** - * This function is called by MAVLink once a complete, uncorrupted (CRC check valid) - * mavlink packet is received. - * - * @param link Hardware link the message came from (e.g. /dev/ttyUSB0 or UDP port). - * messages can be sent back to the system via this link - * @param message MAVLink message, as received from the MAVLink protocol stack - */ -void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) -{ - // Only compile this portion if matching MAVLink packets have been compiled -#ifdef MAVLINK_ENABLED_PIXHAWK - mavlink_message_t* msg = &message; - - if (message.sysid == uasId) - { - switch (message.msgid) - { - case MAVLINK_MSG_ID_RAW_AUX: - { - mavlink_raw_aux_t raw; - mavlink_msg_raw_aux_decode(&message, &raw); - quint64 time = getUnixTime(0); - emit valueChanged(uasId, "Pressure", "raw", raw.baro, time); - emit valueChanged(uasId, "Temperature", "raw", raw.temp, time); - } - break; - case MAVLINK_MSG_ID_IMAGE_TRIGGERED: - { - // FIXME Kind of a hack to load data from disk - mavlink_image_triggered_t img; - mavlink_msg_image_triggered_decode(&message, &img); - emit imageStarted(img.timestamp); - } - break; - case MAVLINK_MSG_ID_PATTERN_DETECTED: - { - mavlink_pattern_detected_t detected; - mavlink_msg_pattern_detected_decode(&message, &detected); - QByteArray b; - b.resize(256); - mavlink_msg_pattern_detected_get_file(&message, b.data()); - b.append('\0'); - QString name = QString(b); - if (detected.type == 0) - emit patternDetected(uasId, name, detected.confidence, detected.detected); - else if (detected.type == 1) - emit letterDetected(uasId, name, detected.confidence, detected.detected); - } - break; - case MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT: { - mavlink_watchdog_heartbeat_t payload; - mavlink_msg_watchdog_heartbeat_decode(msg, &payload); - - emit watchdogReceived(this->uasId, payload.watchdog_id, payload.process_count); - } - break; - - case MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO: { - mavlink_watchdog_process_info_t payload; - mavlink_msg_watchdog_process_info_decode(msg, &payload); - - emit processReceived(this->uasId, payload.watchdog_id, payload.process_id, QString((const char*)payload.name), QString((const char*)payload.arguments), payload.timeout); - } - break; - - case MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS: { - mavlink_watchdog_process_status_t 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); - } - break; -// case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE: { -// mavlink_vision_position_estimate_t pos; -// mavlink_msg_vision_position_estimate_decode(&message, &pos); -// quint64 time = getUnixTime(pos.usec); -// //emit valueChanged(uasId, "vis. time", pos.usec, time); -// emit valueChanged(uasId, "vis. roll", "rad", pos.roll, time); -// emit valueChanged(uasId, "vis. pitch", "rad", pos.pitch, time); -// emit valueChanged(uasId, "vis. yaw", "rad", pos.yaw, time); -// emit valueChanged(uasId, "vis. x", "m", pos.x, time); -// emit valueChanged(uasId, "vis. y", "m", pos.y, time); -// emit valueChanged(uasId, "vis. z", "m", pos.z, time); -// } -// break; -// case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE: { -// mavlink_global_vision_position_estimate_t pos; -// mavlink_msg_global_vision_position_estimate_decode(&message, &pos); -// quint64 time = getUnixTime(pos.usec); -// //emit valueChanged(uasId, "vis. time", pos.usec, time); -// emit valueChanged(uasId, "glob. vis. roll", "rad", pos.roll, time); -// emit valueChanged(uasId, "glob. vis. pitch", "rad", pos.pitch, time); -// emit valueChanged(uasId, "glob. vis. yaw", "rad", pos.yaw, time); -// emit valueChanged(uasId, "glob. vis. x", "m", pos.x, time); -// emit valueChanged(uasId, "glob. vis. y", "m", pos.y, time); -// emit valueChanged(uasId, "glob. vis. z", "m", pos.z, time); -// } -// break; -// case MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE: { -// mavlink_vicon_position_estimate_t pos; -// mavlink_msg_vicon_position_estimate_decode(&message, &pos); -// quint64 time = getUnixTime(pos.usec); -// //emit valueChanged(uasId, "vis. time", pos.usec, time); -// emit valueChanged(uasId, "vicon roll", "rad", pos.roll, time); -// emit valueChanged(uasId, "vicon pitch", "rad", pos.pitch, time); -// emit valueChanged(uasId, "vicon yaw", "rad", pos.yaw, time); -// emit valueChanged(uasId, "vicon x", "m", pos.x, time); -// emit valueChanged(uasId, "vicon y", "m", pos.y, time); -// emit valueChanged(uasId, "vicon z", "m", pos.z, time); -// //emit localPositionChanged(this, pos.x, pos.y, pos.z, time); -// } -// break; -// case MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE: { -// mavlink_vision_speed_estimate_t speed; -// mavlink_msg_vision_speed_estimate_decode(&message, &speed); -// quint64 time = getUnixTime(speed.usec); -// emit valueChanged(uasId, "vis. speed x", "m/s", speed.x, time); -// emit valueChanged(uasId, "vis. speed y", "m/s", speed.y, time); -// emit valueChanged(uasId, "vis. speed z", "m/s", speed.z, time); -// } -// break; -// case MAVLINK_MSG_ID_CONTROL_STATUS: -// { -// mavlink_control_status_t status; -// mavlink_msg_control_status_decode(&message, &status); -// // Emit control status vector -// emit attitudeControlEnabled(static_cast(status.control_att)); -// emit positionXYControlEnabled(static_cast(status.control_pos_xy)); -// emit positionZControlEnabled(static_cast(status.control_pos_z)); -// emit positionYawControlEnabled(static_cast(status.control_pos_yaw)); - -// // Emit localization status vector -// emit localizationChanged(this, status.position_fix); -// emit visionLocalizationChanged(this, status.vision_fix); -// emit gpsLocalizationChanged(this, status.gps_fix); -// } -// break; -// case MAVLINK_MSG_ID_VISUAL_ODOMETRY: -// { -// mavlink_visual_odometry_t pos; -// mavlink_msg_visual_odometry_decode(&message, &pos); -// quint64 time = getUnixTime(pos.frame1_time_us); -// //emit valueChanged(uasId, "vis. time", pos.usec, time); -// emit valueChanged(uasId, "vis-o. roll", "rad", pos.roll, time); -// emit valueChanged(uasId, "vis-o. pitch", "rad", pos.pitch, time); -// emit valueChanged(uasId, "vis-o. yaw", "rad", pos.yaw, time); -// emit valueChanged(uasId, "vis-o. x", "m", pos.x, time); -// emit valueChanged(uasId, "vis-o. y", "m", pos.y, time); -// emit valueChanged(uasId, "vis-o. z", "m", pos.z, time); -// } -// break; -// case MAVLINK_MSG_ID_AUX_STATUS: { -// mavlink_aux_status_t status; -// mavlink_msg_aux_status_decode(&message, &status); -// emit loadChanged(this, status.load/10.0f); -// emit errCountChanged(uasId, "IMU", "I2C0", status.i2c0_err_count); -// emit errCountChanged(uasId, "IMU", "I2C1", status.i2c1_err_count); -// emit errCountChanged(uasId, "IMU", "SPI0", status.spi0_err_count); -// emit errCountChanged(uasId, "IMU", "SPI1", status.spi1_err_count); -// emit errCountChanged(uasId, "IMU", "UART", status.uart_total_err_count); -// emit valueChanged(uasId, "Load", "%", ((float)status.load)/10.0f, getUnixTime()); -// } -// break; - default: - // Let UAS handle the default message set - UAS::receiveMessage(link, message); - break; - } - } - -#else - // Let UAS handle the default message set - UAS::receiveMessage(link, message); - Q_UNUSED(link); - Q_UNUSED(message); -#endif -} - -void PxQuadMAV::sendProcessCommand(int watchdogId, int processId, unsigned int command) -{ -#ifdef MAVLINK_ENABLED_PIXHAWK - mavlink_watchdog_command_t payload; - payload.target_system_id = uasId; - payload.watchdog_id = watchdogId; - payload.process_id = processId; - payload.command_id = (uint8_t)command; - - mavlink_message_t msg; - mavlink_msg_watchdog_command_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &payload); - sendMessage(msg); -#else - Q_UNUSED(watchdogId); - Q_UNUSED(processId); - Q_UNUSED(command); -#endif -} diff --git a/src/uas/PxQuadMAV.h b/src/uas/PxQuadMAV.h deleted file mode 100644 index 1e87f8deadd53abc5e192aac0160c297cb6b1756..0000000000000000000000000000000000000000 --- a/src/uas/PxQuadMAV.h +++ /dev/null @@ -1,46 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -#ifndef PXQUADMAV_H -#define PXQUADMAV_H - -#include "UAS.h" - -class PxQuadMAV : public UAS -{ - Q_OBJECT - Q_INTERFACES(UASInterface) -public: - PxQuadMAV(MAVLinkProtocol* mavlink, QThread* thread, int id); -public slots: - /** @brief Receive a MAVLink message from this MAV */ - void receiveMessage(LinkInterface* link, mavlink_message_t message); - /** @brief Send a command to an onboard process */ - void sendProcessCommand(int watchdogId, int processId, unsigned int command); -signals: - void watchdogReceived(int systemId, int watchdogId, unsigned int processCount); - void processReceived(int systemId, int watchdogId, int processId, QString name, QString arguments, int timeout); - void processChanged(int systemId, int watchdogId, int processId, int state, bool muted, int crashed, int pid); -}; - -#endif // PXQUADMAV_H diff --git a/src/uas/QGCMAVLinkUASFactory.cc b/src/uas/QGCMAVLinkUASFactory.cc index 4f07fdf31a4957577a93e24f4c323a8eaf934799..190b7ce16ce733003af384249010891d7c570539 100644 --- a/src/uas/QGCMAVLinkUASFactory.cc +++ b/src/uas/QGCMAVLinkUASFactory.cc @@ -39,20 +39,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte uas = mav; } break; - case MAV_AUTOPILOT_PIXHAWK: - { - PxQuadMAV* mav = new PxQuadMAV(mavlink, worker, sysid); - // Set the system type - mav->setSystemType((int)heartbeat->type); - - // Connect this robot to the UAS object - // it is IMPORTANT here to use the right object type, - // else the slot of the parent object is called (and thus the special - // packets never reach their goal) - connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t))); - uas = mav; - } - break; case MAV_AUTOPILOT_PX4: { QGXPX4UAS* px4 = new QGXPX4UAS(mavlink, worker, sysid); diff --git a/src/uas/QGCMAVLinkUASFactory.h b/src/uas/QGCMAVLinkUASFactory.h index 321321cd5dd8d1390ca6ad7f6ef275565dad5b58..55242be34c88436f699c9786a025ad46d369f0ce 100644 --- a/src/uas/QGCMAVLinkUASFactory.h +++ b/src/uas/QGCMAVLinkUASFactory.h @@ -10,7 +10,6 @@ // INCLUDE ALL MAV/UAS CLASSES USING MAVLINK #include "UAS.h" -#include "PxQuadMAV.h" class QGCMAVLinkUASFactory : public QObject { diff --git a/src/uas/UAS.h b/src/uas/UAS.h index 9d9681caa6b3429b3bffb3b02cbf9a7f13ed2477..825da65d8688265098c27f8d10e30a8a89fd7b23 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -334,65 +334,6 @@ public: bool isRotaryWing(); bool isFixedWing(); -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - px::GLOverlay getOverlay() - { - QMutexLocker locker(&overlayMutex); - return overlay; - } - - px::GLOverlay getOverlay(qreal& receivedTimestamp) - { - receivedTimestamp = receivedOverlayTimestamp; - QMutexLocker locker(&overlayMutex); - return overlay; - } - - px::ObstacleList getObstacleList() { - QMutexLocker locker(&obstacleListMutex); - return obstacleList; - } - - px::ObstacleList getObstacleList(qreal& receivedTimestamp) { - receivedTimestamp = receivedObstacleListTimestamp; - QMutexLocker locker(&obstacleListMutex); - return obstacleList; - } - - px::Path getPath() { - QMutexLocker locker(&pathMutex); - return path; - } - - px::Path getPath(qreal& receivedTimestamp) { - receivedTimestamp = receivedPathTimestamp; - QMutexLocker locker(&pathMutex); - return path; - } - - px::PointCloudXYZRGB getPointCloud() { - QMutexLocker locker(&pointCloudMutex); - return pointCloud; - } - - px::PointCloudXYZRGB getPointCloud(qreal& receivedTimestamp) { - receivedTimestamp = receivedPointCloudTimestamp; - QMutexLocker locker(&pointCloudMutex); - return pointCloud; - } - - px::RGBDImage getRGBDImage() { - QMutexLocker locker(&rgbdImageMutex); - return rgbdImage; - } - - px::RGBDImage getRGBDImage(qreal& receivedTimestamp) { - receivedTimestamp = receivedRGBDImageTimestamp; - QMutexLocker locker(&rgbdImageMutex); - return rgbdImage; - } -#endif - friend class UASWaypointManager; friend class QGCUASFileManager; @@ -525,28 +466,6 @@ protected: //COMMENTS FOR TEST UNIT bool blockHomePositionChanges; ///< Block changes to the home position bool receivedMode; ///< True if mode was retrieved from current conenction to UAS -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - px::GLOverlay overlay; - QMutex overlayMutex; - qreal receivedOverlayTimestamp; - - px::ObstacleList obstacleList; - QMutex obstacleListMutex; - qreal receivedObstacleListTimestamp; - - px::Path path; - QMutex pathMutex; - qreal receivedPathTimestamp; - - px::PointCloudXYZRGB pointCloud; - QMutex pointCloudMutex; - qreal receivedPointCloudTimestamp; - - px::RGBDImage rgbdImage; - QMutex rgbdImageMutex; - qreal receivedRGBDImageTimestamp; -#endif - /// PARAMETERS QMap* > parameters; ///< All parameters bool paramsOnceRequested; ///< If the parameter list has been read at least once diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 2dc43ac0a7c0b3eaa222d050b537e50c998aa14e..cf35b9894c2280bc8fb700a2de06bca556cf7e03 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -75,9 +75,6 @@ This file is part of the QGROUNDCONTROL project #include "Q3DWidgetFactory.h" #endif -// FIXME Move -#include "PxQuadMAV.h" - #include "LogCompressor.h" // Set up some constants @@ -1549,25 +1546,6 @@ void MainWindow::UASCreated(UASInterface* uas) // Load default custom widgets for this autopilot type loadCustomWidgetsFromDefaults(uas->getSystemTypeName(), uas->getAutopilotTypeName()); - - if (uas->getAutopilotType() == MAV_AUTOPILOT_PIXHAWK) - { - // Dock widgets - if (!detectionDockWidget) - { - detectionDockWidget = new QDockWidget(tr("Object Recognition"), this); - detectionDockWidget->setWidget( new ObjectDetectionView("files/images/patterns", this) ); - detectionDockWidget->setObjectName("OBJECT_DETECTION_DOCK_WIDGET"); - } - - if (!watchdogControlDockWidget) - { - watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this); - watchdogControlDockWidget->setWidget( new WatchdogControl(this) ); - watchdogControlDockWidget->setObjectName("WATCHDOG_CONTROL_DOCKWIDGET"); - } - } - // Reload view state in case new widgets were added loadViewState(); } diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 2dfec84aacdc770286c5b716039e4bf63c56d979..dd1064bf2dfc65e34f0783b62fe0e1e463dc6669 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -48,7 +48,6 @@ This file is part of the QGROUNDCONTROL project #include "UASListWidget.h" #include "MAVLinkProtocol.h" #include "MAVLinkSimulationLink.h" -#include "ObjectDetectionView.h" #include "submainwindow.h" #include "input/JoystickInput.h" #if (defined QGC_MOUSE_ENABLED_WIN) | (defined QGC_MOUSE_ENABLED_LINUX) @@ -57,7 +56,6 @@ This file is part of the QGROUNDCONTROL project #include "DebugConsole.h" #include "ParameterInterface.h" #include "HDDisplay.h" -#include "WatchdogControl.h" #include "HSIDisplay.h" #include "QGCRemoteControlView.h" #include "opmapcontrol.h" diff --git a/src/ui/ObjectDetectionView.cc b/src/ui/ObjectDetectionView.cc deleted file mode 100644 index 4de7dcd38feb2661b20ed24fc7e2627a413136b4..0000000000000000000000000000000000000000 --- a/src/ui/ObjectDetectionView.cc +++ /dev/null @@ -1,214 +0,0 @@ -/*===================================================================== - -PIXHAWK Micro Air Vehicle Flying Robotics Toolkit - -(c) 2009, 2010 PIXHAWK PROJECT - -This file is part of the PIXHAWK project - - PIXHAWK is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - PIXHAWK is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with PIXHAWK. If not, see . - -======================================================================*/ - -/** - * @file - * @brief List of detected objects - * @author Benjamin Knecht - * @author Lorenz Meier - * @author Fabian Landau - * - */ - -#include -#include -#include "ObjectDetectionView.h" -#include "ui_ObjectDetectionView.h" -#include "UASManager.h" -#include "GAudioOutput.h" - -#include -#include - -ObjectDetectionView::ObjectDetectionView(QString folder, QWidget *parent) : - QWidget(parent), - patternList(), - letterList(), - letterTimer(), - uas(NULL), - patternFolder(folder), - separator(" "), - m_ui(new Ui::ObjectDetectionView) -{ - m_ui->setupUi(this); - connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setUAS(UASInterface*))); - letterTimer.start(1000); - connect(&letterTimer, SIGNAL(timeout()), this, SLOT(decreaseLetterTime())); - connect(m_ui->clearButton, SIGNAL(clicked()), this, SLOT(clearLists())); - - this->setVisible(false); -} - -ObjectDetectionView::~ObjectDetectionView() -{ - delete m_ui; -} - -void ObjectDetectionView::changeEvent(QEvent *e) -{ - switch (e->type()) { - case QEvent::LanguageChange: - m_ui->retranslateUi(this); - break; - default: - break; - } -} - -void ObjectDetectionView::setUAS(UASInterface* uas) -{ - if (this->uas != NULL) { - disconnect(this->uas, SIGNAL(patternDetected(int, QString, float, bool)), this, SLOT(newPattern(int, QString, float, bool))); - disconnect(this->uas, SIGNAL(letterDetected(int, QString, float, bool)), this, SLOT(newLetter(int, QString, float, bool))); - } - - this->uas = uas; - connect(uas, SIGNAL(patternDetected(int, QString, float, bool)), this, SLOT(newPattern(int, QString, float, bool))); - connect(uas, SIGNAL(letterDetected(int, QString, float, bool)), this, SLOT(newLetter(int, QString, float, bool))); -} - -void ObjectDetectionView::newPattern(int uasId, QString patternPath, float confidence, bool detected) -{ - if (detected) { - if (!patternList.contains(patternPath)) { - // Emit audio message on detection - if (detected) GAudioOutput::instance()->say("System " + QString::number(uasId) + " detected pattern " + QString(patternPath.split("/", QString::SkipEmptyParts).last()).split(".", QString::SkipEmptyParts).first()); - - patternList.insert(patternPath, Pattern(patternPath, confidence)); - } else { - Pattern pattern = patternList.value(patternPath); - if (confidence > pattern.confidence) - pattern.confidence = confidence; - ++pattern.count; - patternList.insert(patternPath, pattern); - } - - // set list items - QList templist; - foreach (Pattern pattern, patternList) - templist.push_back(pattern); - qSort(templist); - m_ui->listWidget->clear(); - foreach (Pattern pattern, templist) - m_ui->listWidget->addItem(pattern.name + separator + "(" + QString::number(pattern.count) + ")" + separator + QString::number(pattern.confidence)); - - // load image - QString filePath = patternFolder + "/" + patternPath.split("/", QString::SkipEmptyParts).last(); - QPixmap image = QPixmap(filePath); - if (image.width() > image.height()) - image = image.scaledToWidth(m_ui->imageLabel->width()); - else - image = image.scaledToHeight(m_ui->imageLabel->height()); - m_ui->imageLabel->setPixmap(image); - - // set textlabel - QString patternName = patternPath.split("/", QString::SkipEmptyParts).last(); // Remove preceding folder names - patternName = patternName.split(".", QString::SkipEmptyParts).first(); // Remove file ending - m_ui->nameLabel->setText("Pattern: " + patternName); - } -} - -void ObjectDetectionView::newLetter(int uasId, QString letter, float confidence, bool detected) -{ - Q_UNUSED(confidence); - - if (detected) { - if (!letterList.contains(letter)) { - // Emit audio message on detection - if (detected) GAudioOutput::instance()->say("System " + QString::number(uasId) + " detected letter " + letter); - - letterList.insert(letter, Pattern(letter, 0)); - } else { - Pattern pattern = letterList.value(letter); - pattern.confidence = 0; - ++pattern.count; - letterList.insert(letter, pattern); - } - - updateLetterList(); - - // display letter - m_ui->letterLabel->setText(letter); - - // set textlabel - m_ui->nameLabel->setText("Letter: " + letter); - } -} - -void ObjectDetectionView::decreaseLetterTime() -{ - foreach (Pattern pattern, letterList) { - pattern.confidence -= 1; - letterList.insert(pattern.name, pattern); - } - - updateLetterList(); -} - -void ObjectDetectionView::updateLetterList() -{ - // set list items - QList templist; - foreach (Pattern pattern, letterList) - templist.push_back(pattern); - qSort(templist); - m_ui->letterListWidget->clear(); - foreach (Pattern pattern, templist) - m_ui->letterListWidget->addItem(pattern.name + separator + "(" + QString::number(pattern.count) + ")" + separator + QString::number(pattern.confidence)); -} - -void ObjectDetectionView::clearLists() -{ - patternList.clear(); - letterList.clear(); - - m_ui->listWidget->clear(); - m_ui->letterListWidget->clear(); - - m_ui->imageLabel->clear();; - m_ui->letterLabel->clear(); - m_ui->nameLabel->clear(); -} - -void ObjectDetectionView::takeAction() -{ - QAction* act = dynamic_cast(sender()); - if (act) { - QString patternPath = act->text().trimmed().split(separator, QString::SkipEmptyParts).first(); // Remove additional information - QString patternName = patternPath.split("//", QString::SkipEmptyParts).last(); // Remove preceding folder names - patternName = patternName.split(".", QString::SkipEmptyParts).first(); // Remove file ending - - // Set name and label - m_ui->nameLabel->setText(patternName); - m_ui->imageLabel->setPixmap(act->icon().pixmap(64, 64)); - } -} - -void ObjectDetectionView::resizeEvent(QResizeEvent * event ) -{ - if (event->isAccepted()) { - // Enforce square shape of image label - m_ui->imageLabel->resize(m_ui->imageLabel->width(), m_ui->imageLabel->width()); - } -} - diff --git a/src/ui/ObjectDetectionView.h b/src/ui/ObjectDetectionView.h deleted file mode 100644 index 0f0bf9bfa90e0585eabba49a2172745a6ddef8c4..0000000000000000000000000000000000000000 --- a/src/ui/ObjectDetectionView.h +++ /dev/null @@ -1,99 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief List of detected objects - * @author Benjamin Knecht - * @author Lorenz Meier - * @author Fabian Landau - * - */ - -#ifndef _OBJECTDETECTIONVIEW_H_ -#define _OBJECTDETECTIONVIEW_H_ - -#include -#include -#include -#include "UASInterface.h" - -namespace Ui -{ -class ObjectDetectionView; -} - -/** - * @brief Lists the detected objects and their confidence - */ -class ObjectDetectionView : public QWidget -{ - Q_OBJECT - Q_DISABLE_COPY(ObjectDetectionView) - - struct Pattern { - Pattern() : name(QString()), confidence(0.0f), count(0) {} - Pattern(QString name, float confidence) : name(name), confidence(confidence), count(1) {} - - bool operator<(const Pattern& other) const { - return this->confidence > other.confidence; // this comparison is intentionally wrong to sort the QList from highest confidence to lowest - } - - QString name; - float confidence; - unsigned int count; - }; - -public: - explicit ObjectDetectionView(QString folder="files/images/patterns", QWidget *parent = 0); - virtual ~ObjectDetectionView(); - - /** @brief Resize widget contents */ - void resizeEvent(QResizeEvent * event ); - -public slots: - /** @brief Set the UAS this view is currently associated to */ - void setUAS(UASInterface* uas); - /** @brief Report new detection */ - void newPattern(int uasId, QString patternPath, float confidence, bool detected); - void newLetter(int uasId, QString letter, float confidence, bool detected); - void decreaseLetterTime(); - void updateLetterList(); - void clearLists(); - /** @brief Accept an internal action, update name and preview image label */ - void takeAction(); - -protected: - virtual void changeEvent(QEvent *e); - QMap patternList; ///< The detected patterns with their confidence and detection count - QMap letterList; ///< The detected letters with their confidence and detection count - QTimer letterTimer; ///< A timer to "forget" old letters - UASInterface* uas; ///< The monitored UAS - QString patternFolder; ///< The base folder where pattern images are stored in - const QString separator; - -private: - Ui::ObjectDetectionView *m_ui; -}; - -#endif // _OBJECTDETECTIONVIEW_H_ diff --git a/src/ui/ObjectDetectionView.ui b/src/ui/ObjectDetectionView.ui deleted file mode 100644 index e35e48dc3c013fee3f492820460e4a07c20f0403..0000000000000000000000000000000000000000 --- a/src/ui/ObjectDetectionView.ui +++ /dev/null @@ -1,116 +0,0 @@ - - - ObjectDetectionView - - - - 0 - 0 - 246 - 403 - - - - Form - - - - - - - - - - - - - 10 - 10 - - - - - 110 - 110 - - - - - 2 - 2 - - - - - 10 - 10 - - - - - - - - - - - - 10 - 10 - - - - - 110 - 110 - - - - - 2 - 2 - - - - - 10 - 10 - - - - font: 72pt; -color: white; - - - - - - Qt::AlignCenter - - - - - - - No objects recognized - - - - - - - - 80 - 16777215 - - - - Clear - - - - - - - - diff --git a/src/ui/QGCRGBDView.cc b/src/ui/QGCRGBDView.cc index 5427082a80ecfb74af42831f08469bb666631cbe..6309702f0d17f9be0c4c2ab16c2e88b35415e44f 100644 --- a/src/ui/QGCRGBDView.cc +++ b/src/ui/QGCRGBDView.cc @@ -247,76 +247,5 @@ float colormapJet[128][3] = { void QGCRGBDView::updateData(UASInterface *uas) { -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - px::RGBDImage rgbdImage = uas->getRGBDImage(); - - if (rgbdImage.rows() == 0 || rgbdImage.cols() == 0 || (!rgbEnabled && !depthEnabled)) - { - return; - } - - QImage fill; - - if (rgbEnabled) - { -// fill = QImage(reinterpret_cast(rgbdImage.imagedata1().c_str()), -// rgbdImage.cols(), rgbdImage.rows(), QImage::Format_Mono); - - - // Construct PGM header - QString header("P5\n%1 %2\n%3\n"); - int imgColors = 255; - header = header.arg(rgbdImage.cols()).arg(rgbdImage.rows()).arg(imgColors); - - //QByteArray tmpImage(rgbdImage.imagedata1().c_str(), rgbdImage.cols()*rgbdImage.rows()); - QByteArray tmpImage(header.toStdString().c_str(), header.toStdString().size()); - tmpImage.append(rgbdImage.imagedata1().c_str(), rgbdImage.cols()*rgbdImage.rows()); - - //qDebug() << "IMAGE SIZE:" << tmpImage.size() << "HEADER SIZE: (15):" << header.size() << "HEADER: " << header; - -// if (imageRecBuffer.isNull()) -// { -// qDebug()<< "could not convertToPGM()"; -// return QImage(); -// } - - if (!fill.loadFromData(tmpImage, "PGM")) - { - qDebug()<< "could not create extracted image"; -// return QImage(); - } - } - - if (depthEnabled) - { - QByteArray coloredDepth(rgbdImage.cols() * rgbdImage.rows() * 3, 0); - - for (uint32_t r = 0; r < rgbdImage.rows(); ++r) - { - const float* depth = reinterpret_cast(rgbdImage.imagedata2().c_str() + r * rgbdImage.step2()); - uint8_t* pixel = reinterpret_cast(coloredDepth.data()) + r * rgbdImage.cols() * 3; - for (uint32_t c = 0; c < rgbdImage.cols(); ++c) - { - if (depth[c] != 0) - { - int idx = fminf(depth[c], 10.0f) / 10.0f * 127.0f; - idx = 127 - idx; - - pixel[0] = colormapJet[idx][2] * 255.0f; - pixel[1] = colormapJet[idx][1] * 255.0f; - pixel[2] = colormapJet[idx][0] * 255.0f; - } - - pixel += 3; - } - } - - fill = QImage(reinterpret_cast(coloredDepth.constData()), - rgbdImage.cols(), rgbdImage.rows(), QImage::Format_RGB888); - } - - glImage = QGLWidget::convertToGLFormat(fill); -#else Q_UNUSED(uas); -#endif } diff --git a/src/ui/WaypointEditableView.cc b/src/ui/WaypointEditableView.cc index 9c9e17cf89e3cbffc4e6b1a11e39620e08b2ca2c..0813598e00e13940ac9bfd5c8d3c507687657a07 100644 --- a/src/ui/WaypointEditableView.cc +++ b/src/ui/WaypointEditableView.cc @@ -78,11 +78,6 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : m_ui->comboBox_action->addItem(tr("IF: Delay over"),MAV_CMD_CONDITION_DELAY); //m_ui->comboBox_action->addItem(tr("IF: Yaw angle is"),MAV_CMD_CONDITION_YAW); m_ui->comboBox_action->addItem(tr("DO: Jump to Index"),MAV_CMD_DO_JUMP); -#ifdef MAVLINK_ENABLED_PIXHAWK - m_ui->comboBox_action->addItem(tr("NAV: Sweep"),MAV_CMD_NAV_SWEEP); - m_ui->comboBox_action->addItem(tr("Do: Start Search"),MAV_CMD_DO_START_SEARCH); - m_ui->comboBox_action->addItem(tr("Do: Finish Search"),MAV_CMD_DO_FINISH_SEARCH); -#endif m_ui->comboBox_action->addItem(tr("Other"), MAV_CMD_ENUM_END); // add frames @@ -191,17 +186,6 @@ void WaypointEditableView::updateActionView(int action) case MAV_CMD_DO_JUMP: if(MissionDoJumpWidget) MissionDoJumpWidget->show(); break; - #ifdef MAVLINK_ENABLED_PIXHAWK - case MAV_CMD_NAV_SWEEP: - if(MissionNavSweepWidget) MissionNavSweepWidget->show(); - break; - case MAV_CMD_DO_START_SEARCH: - if(MissionDoStartSearchWidget) MissionDoStartSearchWidget->show(); - break; - case MAV_CMD_DO_FINISH_SEARCH: - if(MissionDoFinishSearchWidget) MissionDoFinishSearchWidget->show(); - break; - #endif default: if(MissionOtherWidget) MissionOtherWidget->show(); @@ -305,29 +289,6 @@ void WaypointEditableView::initializeActionView(int actionID) m_ui->customActionWidget->layout()->addWidget(MissionDoJumpWidget); } break; - #ifdef MAVLINK_ENABLED_PIXHAWK - case MAV_CMD_NAV_SWEEP: - if (!MissionNavSweepWidget) - { - MissionNavSweepWidget = new QGCMissionNavSweep(this); - m_ui->customActionWidget->layout()->addWidget(MissionNavSweepWidget); - } - break; - case MAV_CMD_DO_START_SEARCH: - if (!MissionDoStartSearchWidget) - { - MissionDoStartSearchWidget = new QGCMissionDoStartSearch(this); - m_ui->customActionWidget->layout()->addWidget(MissionDoStartSearchWidget); - } - break; - case MAV_CMD_DO_FINISH_SEARCH: - if (!MissionDoFinishSearchWidget) - { - MissionDoFinishSearchWidget = new QGCMissionDoFinishSearch(this); - m_ui->customActionWidget->layout()->addWidget(MissionDoFinishSearchWidget); - } - break; -#endif case MAV_CMD_ENUM_END: default: if (!MissionOtherWidget) diff --git a/src/ui/WaypointViewOnlyView.cc b/src/ui/WaypointViewOnlyView.cc index 32f3b078065b844c3f5d77c60c4e39eae4ad848d..5c4d94d402811b08b1abedea1a2bb3a29844553a 100644 --- a/src/ui/WaypointViewOnlyView.cc +++ b/src/ui/WaypointViewOnlyView.cc @@ -350,37 +350,6 @@ void WaypointViewOnlyView::updateValues() m_ui->displayBar->setText(QString("Delay: %1 sec").arg(wp->getParam1())); break; } -#ifdef MAVLINK_ENABLED_PIXHAWK - case MAV_CMD_DO_START_SEARCH: - { - m_ui->displayBar->setText(QString("Start searching for pattern. Success when got more than %2 detections with confidence %1").arg(wp->getParam1()).arg(wp->getParam2())); - break; - } - case MAV_CMD_DO_FINISH_SEARCH: - { - m_ui->displayBar->setText(QString("Check if search was successful. yes -> jump to %1, no -> jump to %2. Jumps left: %3").arg(wp->getParam1()).arg(wp->getParam2()).arg(wp->getParam3())); - break; - } - case MAV_CMD_NAV_SWEEP: - { - switch (wp->getFrame()) - { - case MAV_FRAME_GLOBAL_RELATIVE_ALT: - case MAV_FRAME_GLOBAL: - { - m_ui->displayBar->setText(QString("Sweep. Corners: (lat %1o, lon %2o) and (lat %3o, lon %4o); alt: %5; scan radius: %6").arg(wp->getParam3(),0, 'f', 7).arg(wp->getParam4(),0, 'f', 7).arg(wp->getParam5(),0, 'f', 7).arg(wp->getParam6(),0, 'f', 7).arg(wp->getParam7(),0, 'f', 2).arg(wp->getParam1())); - break; - } - case MAV_FRAME_LOCAL_NED: - default: - { - m_ui->displayBar->setText(QString("Sweep. Corners: (%1, %2) and (%3, %4); z: %5; scan radius: %6").arg(wp->getParam3()).arg(wp->getParam4()).arg(wp->getParam5()).arg(wp->getParam6()).arg(wp->getParam7()).arg(wp->getParam1())); - break; - } - } //end Frame switch - break; - } -#endif default: { m_ui->displayBar->setText(QString("Unknown Command ID (%1) : %2, %3, %4, %5, %6, %7, %8").arg(wp->getAction()).arg(wp->getParam1()).arg(wp->getParam2()).arg(wp->getParam3()).arg(wp->getParam4()).arg(wp->getParam5()).arg(wp->getParam6()).arg(wp->getParam7())); diff --git a/src/ui/generated/.gitignore b/src/ui/generated/.gitignore deleted file mode 100644 index 7233d633d94704fcd6549bd8194639ce8039b4fc..0000000000000000000000000000000000000000 --- a/src/ui/generated/.gitignore +++ /dev/null @@ -1 +0,0 @@ -ui_*.h diff --git a/src/ui/generated/AudioOutputWidget.h b/src/ui/generated/AudioOutputWidget.h deleted file mode 100644 index 18d0259cad731487063acf7cf11500ceb708c60b..0000000000000000000000000000000000000000 --- a/src/ui/generated/AudioOutputWidget.h +++ /dev/null @@ -1,77 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'AudioOutputWidget.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef AUDIOOUTPUTWIDGET_H -#define AUDIOOUTPUTWIDGET_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_AudioOutputWidget -{ -public: - QGridLayout *gridLayout; - QSpacerItem *horizontalSpacer; - QSpacerItem *verticalSpacer; - QPushButton *muteButton; - - void setupUi(QWidget *AudioOutputWidget) { - if (AudioOutputWidget->objectName().isEmpty()) - AudioOutputWidget->setObjectName(QString::fromUtf8("AudioOutputWidget")); - AudioOutputWidget->resize(195, 95); - gridLayout = new QGridLayout(AudioOutputWidget); - gridLayout->setContentsMargins(6, 6, 6, 6); - gridLayout->setObjectName(QString::fromUtf8("gridLayout")); - horizontalSpacer = new QSpacerItem(53, 20, QSizePolicy::Expanding, QSizePolicy::Minimum); - - gridLayout->addItem(horizontalSpacer, 0, 2, 1, 2); - - verticalSpacer = new QSpacerItem(180, 43, QSizePolicy::Minimum, QSizePolicy::Expanding); - - gridLayout->addItem(verticalSpacer, 1, 0, 1, 4); - - muteButton = new QPushButton(AudioOutputWidget); - muteButton->setObjectName(QString::fromUtf8("muteButton")); - QIcon icon; - icon.addFile(QString::fromUtf8(":/files/images/status/audio-volume-muted.svg"), QSize(), QIcon::Normal, QIcon::Off); - muteButton->setIcon(icon); - muteButton->setIconSize(QSize(16, 16)); - - gridLayout->addWidget(muteButton, 0, 0, 1, 1); - - - retranslateUi(AudioOutputWidget); - - QMetaObject::connectSlotsByName(AudioOutputWidget); - } // setupUi - - void retranslateUi(QWidget *AudioOutputWidget) { - AudioOutputWidget->setWindowTitle(QApplication::translate("AudioOutputWidget", "Form", 0, QApplication::UnicodeUTF8)); - muteButton->setText(QApplication::translate("AudioOutputWidget", "Mute", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class AudioOutputWidget: public Ui_AudioOutputWidget {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // AUDIOOUTPUTWIDGET_H diff --git a/src/ui/generated/CommSettings.h b/src/ui/generated/CommSettings.h deleted file mode 100644 index 2c7267c282d9ef194e4fc0174a866e22dcd3dcc2..0000000000000000000000000000000000000000 --- a/src/ui/generated/CommSettings.h +++ /dev/null @@ -1,8 +0,0 @@ -/**************************************************************************** -** Form interface generated from reading ui file 'src/ui/CommSettings.ui' -** -** Created: Tue Jun 1 20:21:32 2010 -** -** WARNING! All changes made in this file will be lost! -****************************************************************************/ - diff --git a/src/ui/generated/DebugConsole.h b/src/ui/generated/DebugConsole.h deleted file mode 100644 index be6ac82752874c05454832e3a42d5f861561133d..0000000000000000000000000000000000000000 --- a/src/ui/generated/DebugConsole.h +++ /dev/null @@ -1,181 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'DebugConsole.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef DEBUGCONSOLE_H -#define DEBUGCONSOLE_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_DebugConsole -{ -public: - QGridLayout *gridLayout; - QHBoxLayout *horizontalLayout_2; - QComboBox *linkComboBox; - QLabel *speedLabel; - QCheckBox *mavlinkCheckBox; - QCheckBox *hexCheckBox; - QCheckBox *holdCheckBox; - QPlainTextEdit *receiveText; - QLineEdit *sentText; - QLineEdit *sendText; - QHBoxLayout *horizontalLayout; - QPushButton *transmitButton; - QPushButton *holdButton; - QPushButton *clearButton; - - void setupUi(QWidget *DebugConsole) { - if (DebugConsole->objectName().isEmpty()) - DebugConsole->setObjectName(QString::fromUtf8("DebugConsole")); - DebugConsole->resize(435, 185); - gridLayout = new QGridLayout(DebugConsole); - gridLayout->setContentsMargins(6, 6, 6, 6); - gridLayout->setObjectName(QString::fromUtf8("gridLayout")); - gridLayout->setHorizontalSpacing(6); - gridLayout->setVerticalSpacing(4); - horizontalLayout_2 = new QHBoxLayout(); - horizontalLayout_2->setObjectName(QString::fromUtf8("horizontalLayout_2")); - linkComboBox = new QComboBox(DebugConsole); - linkComboBox->setObjectName(QString::fromUtf8("linkComboBox")); - linkComboBox->setMaximumSize(QSize(130, 16777215)); - - horizontalLayout_2->addWidget(linkComboBox); - - speedLabel = new QLabel(DebugConsole); - speedLabel->setObjectName(QString::fromUtf8("speedLabel")); - - horizontalLayout_2->addWidget(speedLabel); - - mavlinkCheckBox = new QCheckBox(DebugConsole); - mavlinkCheckBox->setObjectName(QString::fromUtf8("mavlinkCheckBox")); - - horizontalLayout_2->addWidget(mavlinkCheckBox); - - hexCheckBox = new QCheckBox(DebugConsole); - hexCheckBox->setObjectName(QString::fromUtf8("hexCheckBox")); - - horizontalLayout_2->addWidget(hexCheckBox); - - holdCheckBox = new QCheckBox(DebugConsole); - holdCheckBox->setObjectName(QString::fromUtf8("holdCheckBox")); - - horizontalLayout_2->addWidget(holdCheckBox); - - horizontalLayout_2->setStretch(0, 10); - - gridLayout->addLayout(horizontalLayout_2, 0, 0, 1, 2); - - receiveText = new QPlainTextEdit(DebugConsole); - receiveText->setObjectName(QString::fromUtf8("receiveText")); - - gridLayout->addWidget(receiveText, 1, 0, 1, 2); - - sentText = new QLineEdit(DebugConsole); - sentText->setObjectName(QString::fromUtf8("sentText")); - sentText->setReadOnly(true); - - gridLayout->addWidget(sentText, 2, 0, 1, 2); - - sendText = new QLineEdit(DebugConsole); - sendText->setObjectName(QString::fromUtf8("sendText")); - - gridLayout->addWidget(sendText, 3, 0, 1, 1); - - horizontalLayout = new QHBoxLayout(); - horizontalLayout->setObjectName(QString::fromUtf8("horizontalLayout")); - transmitButton = new QPushButton(DebugConsole); - transmitButton->setObjectName(QString::fromUtf8("transmitButton")); - QIcon icon; - icon.addFile(QString::fromUtf8(":/files/images/devices/network-wireless.svg"), QSize(), QIcon::Normal, QIcon::Off); - transmitButton->setIcon(icon); - - horizontalLayout->addWidget(transmitButton); - - holdButton = new QPushButton(DebugConsole); - holdButton->setObjectName(QString::fromUtf8("holdButton")); - holdButton->setCheckable(true); - - horizontalLayout->addWidget(holdButton); - - clearButton = new QPushButton(DebugConsole); - clearButton->setObjectName(QString::fromUtf8("clearButton")); - - horizontalLayout->addWidget(clearButton); - - - gridLayout->addLayout(horizontalLayout, 3, 1, 1, 1); - - - retranslateUi(DebugConsole); - QObject::connect(clearButton, SIGNAL(clicked()), receiveText, SLOT(clear())); - - QMetaObject::connectSlotsByName(DebugConsole); - } // setupUi - - void retranslateUi(QWidget *DebugConsole) { - DebugConsole->setWindowTitle(QApplication::translate("DebugConsole", "Form", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - linkComboBox->setToolTip(QApplication::translate("DebugConsole", "Select the link to monitor", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - speedLabel->setText(QApplication::translate("DebugConsole", "0.0 kB/s", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - mavlinkCheckBox->setToolTip(QApplication::translate("DebugConsole", "Ignore MAVLINK protocol messages in display", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - mavlinkCheckBox->setText(QApplication::translate("DebugConsole", "No MAVLINK", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - hexCheckBox->setToolTip(QApplication::translate("DebugConsole", "Display and send bytes in HEX representation", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - hexCheckBox->setText(QApplication::translate("DebugConsole", "HEX", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - holdCheckBox->setToolTip(QApplication::translate("DebugConsole", "Saves CPU ressources, automatically set view to hold if data rate is too high to prevent fast scrolling", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP -#ifndef QT_NO_STATUSTIP - holdCheckBox->setStatusTip(QApplication::translate("DebugConsole", "Saves CPU ressources, automatically set view to hold if data rate is too high to prevent fast scrolling", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_STATUSTIP -#ifndef QT_NO_WHATSTHIS - holdCheckBox->setWhatsThis(QApplication::translate("DebugConsole", "Enable auto hold to lower the CPU consumption", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_WHATSTHIS - holdCheckBox->setText(QApplication::translate("DebugConsole", "Auto hold", 0, QApplication::UnicodeUTF8)); - sentText->setText(QApplication::translate("DebugConsole", "Enter data/text below to send", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - sendText->setToolTip(QApplication::translate("DebugConsole", "Type the bytes to send here, use 0xAA format for HEX (Check HEX checkbox above)", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP -#ifndef QT_NO_TOOLTIP - transmitButton->setToolTip(QApplication::translate("DebugConsole", "Send the ASCII text or HEX values over the link", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - transmitButton->setText(QApplication::translate("DebugConsole", "Send", 0, QApplication::UnicodeUTF8)); - holdButton->setText(QApplication::translate("DebugConsole", "Hold", 0, QApplication::UnicodeUTF8)); - clearButton->setText(QApplication::translate("DebugConsole", "Clear", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class DebugConsole: public Ui_DebugConsole {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // DEBUGCONSOLE_H diff --git a/src/ui/generated/HDDisplay.h b/src/ui/generated/HDDisplay.h deleted file mode 100644 index ae61edd024d4c5762797d86c502b69d7bbc14a18..0000000000000000000000000000000000000000 --- a/src/ui/generated/HDDisplay.h +++ /dev/null @@ -1,60 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'HDDisplay.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef HDDISPLAY_H -#define HDDISPLAY_H - -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_HDDisplay -{ -public: - QHBoxLayout *horizontalLayout; - QGraphicsView *view; - - void setupUi(QWidget *HDDisplay) { - if (HDDisplay->objectName().isEmpty()) - HDDisplay->setObjectName(QString::fromUtf8("HDDisplay")); - HDDisplay->resize(400, 300); - horizontalLayout = new QHBoxLayout(HDDisplay); - horizontalLayout->setObjectName(QString::fromUtf8("horizontalLayout")); - view = new QGraphicsView(HDDisplay); - view->setObjectName(QString::fromUtf8("view")); - - horizontalLayout->addWidget(view); - - - retranslateUi(HDDisplay); - - QMetaObject::connectSlotsByName(HDDisplay); - } // setupUi - - void retranslateUi(QWidget *HDDisplay) { - HDDisplay->setWindowTitle(QApplication::translate("HDDisplay", "Form", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class HDDisplay: public Ui_HDDisplay {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // HDDISPLAY_H diff --git a/src/ui/generated/JoystickWidget.h b/src/ui/generated/JoystickWidget.h deleted file mode 100644 index 1eb2ee277c556d2bae954a5b595f099c1fdff28c..0000000000000000000000000000000000000000 --- a/src/ui/generated/JoystickWidget.h +++ /dev/null @@ -1,109 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'JoystickWidget.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef JOYSTICKWIDGET_H -#define JOYSTICKWIDGET_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_JoystickWidget -{ -public: - QDialogButtonBox *buttonBox; - QProgressBar *thrust; - QSlider *ySlider; - QSlider *xSlider; - QLCDNumber *xValue; - QLCDNumber *yValue; - QDial *dial; - QGroupBox *button0Label; - - void setupUi(QDialog *JoystickWidget) { - if (JoystickWidget->objectName().isEmpty()) - JoystickWidget->setObjectName(QString::fromUtf8("JoystickWidget")); - JoystickWidget->resize(400, 300); - buttonBox = new QDialogButtonBox(JoystickWidget); - buttonBox->setObjectName(QString::fromUtf8("buttonBox")); - buttonBox->setGeometry(QRect(30, 240, 341, 32)); - buttonBox->setOrientation(Qt::Horizontal); - buttonBox->setStandardButtons(QDialogButtonBox::Cancel|QDialogButtonBox::Ok); - thrust = new QProgressBar(JoystickWidget); - thrust->setObjectName(QString::fromUtf8("thrust")); - thrust->setGeometry(QRect(350, 20, 31, 181)); - thrust->setValue(0); - thrust->setOrientation(Qt::Vertical); - ySlider = new QSlider(JoystickWidget); - ySlider->setObjectName(QString::fromUtf8("ySlider")); - ySlider->setGeometry(QRect(160, 190, 160, 17)); - ySlider->setMaximum(100); - ySlider->setOrientation(Qt::Horizontal); - xSlider = new QSlider(JoystickWidget); - xSlider->setObjectName(QString::fromUtf8("xSlider")); - xSlider->setGeometry(QRect(140, 40, 17, 160)); - xSlider->setMaximum(100); - xSlider->setOrientation(Qt::Vertical); - xValue = new QLCDNumber(JoystickWidget); - xValue->setObjectName(QString::fromUtf8("xValue")); - xValue->setGeometry(QRect(160, 50, 41, 23)); - xValue->setFrameShadow(QFrame::Plain); - xValue->setSmallDecimalPoint(true); - xValue->setNumDigits(3); - xValue->setSegmentStyle(QLCDNumber::Flat); - yValue = new QLCDNumber(JoystickWidget); - yValue->setObjectName(QString::fromUtf8("yValue")); - yValue->setGeometry(QRect(270, 160, 41, 23)); - yValue->setFrameShadow(QFrame::Plain); - yValue->setSmallDecimalPoint(true); - yValue->setNumDigits(3); - yValue->setSegmentStyle(QLCDNumber::Flat); - dial = new QDial(JoystickWidget); - dial->setObjectName(QString::fromUtf8("dial")); - dial->setGeometry(QRect(210, 50, 101, 101)); - button0Label = new QGroupBox(JoystickWidget); - button0Label->setObjectName(QString::fromUtf8("button0Label")); - button0Label->setGeometry(QRect(60, 20, 41, 16)); - button0Label->setAutoFillBackground(false); - button0Label->setFlat(false); - - retranslateUi(JoystickWidget); - QObject::connect(buttonBox, SIGNAL(accepted()), JoystickWidget, SLOT(accept())); - QObject::connect(buttonBox, SIGNAL(rejected()), JoystickWidget, SLOT(reject())); - - QMetaObject::connectSlotsByName(JoystickWidget); - } // setupUi - - void retranslateUi(QDialog *JoystickWidget) { - JoystickWidget->setWindowTitle(QApplication::translate("JoystickWidget", "Dialog", 0, QApplication::UnicodeUTF8)); - button0Label->setStyleSheet(QApplication::translate("JoystickWidget", "QGroupBox { border: 1px solid #EEEEEE; border-radius: 4px; padding: 0px; margin: 0px; background-color: #FF2222;}", 0, QApplication::UnicodeUTF8)); - button0Label->setTitle(QString()); - } // retranslateUi - -}; - -namespace Ui -{ -class JoystickWidget: public Ui_JoystickWidget {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // JOYSTICKWIDGET_H diff --git a/src/ui/generated/LineChart.h b/src/ui/generated/LineChart.h deleted file mode 100644 index 7650c6a856bd9112966086c7ff682e87d8ceafe9..0000000000000000000000000000000000000000 --- a/src/ui/generated/LineChart.h +++ /dev/null @@ -1,120 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'LineChart.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef LINECHART_H -#define LINECHART_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_linechart -{ -public: - QHBoxLayout *horizontalLayout_2; - QGroupBox *curveGroupBox; - QVBoxLayout *verticalLayout; - QScrollArea *curveListWidget; - QWidget *scrollAreaWidgetContents; - QGroupBox *diagramGroupBox; - - void setupUi(QWidget *linechart) { - if (linechart->objectName().isEmpty()) - linechart->setObjectName(QString::fromUtf8("linechart")); - linechart->resize(662, 381); - QSizePolicy sizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); - sizePolicy.setHorizontalStretch(3); - sizePolicy.setVerticalStretch(2); - sizePolicy.setHeightForWidth(linechart->sizePolicy().hasHeightForWidth()); - linechart->setSizePolicy(sizePolicy); - linechart->setMinimumSize(QSize(300, 200)); - horizontalLayout_2 = new QHBoxLayout(linechart); - horizontalLayout_2->setSpacing(3); - horizontalLayout_2->setObjectName(QString::fromUtf8("horizontalLayout_2")); - horizontalLayout_2->setContentsMargins(2, 0, 2, 2); - curveGroupBox = new QGroupBox(linechart); - curveGroupBox->setObjectName(QString::fromUtf8("curveGroupBox")); - QSizePolicy sizePolicy1(QSizePolicy::Expanding, QSizePolicy::MinimumExpanding); - sizePolicy1.setHorizontalStretch(1); - sizePolicy1.setVerticalStretch(0); - sizePolicy1.setHeightForWidth(curveGroupBox->sizePolicy().hasHeightForWidth()); - curveGroupBox->setSizePolicy(sizePolicy1); - curveGroupBox->setMinimumSize(QSize(250, 300)); - curveGroupBox->setAlignment(Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop); - verticalLayout = new QVBoxLayout(curveGroupBox); - verticalLayout->setSpacing(2); - verticalLayout->setContentsMargins(0, 0, 0, 0); - verticalLayout->setObjectName(QString::fromUtf8("verticalLayout")); - curveListWidget = new QScrollArea(curveGroupBox); - curveListWidget->setObjectName(QString::fromUtf8("curveListWidget")); - QSizePolicy sizePolicy2(QSizePolicy::Preferred, QSizePolicy::Expanding); - sizePolicy2.setHorizontalStretch(0); - sizePolicy2.setVerticalStretch(0); - sizePolicy2.setHeightForWidth(curveListWidget->sizePolicy().hasHeightForWidth()); - curveListWidget->setSizePolicy(sizePolicy2); - curveListWidget->setMinimumSize(QSize(240, 250)); - curveListWidget->setBaseSize(QSize(150, 200)); - curveListWidget->setAutoFillBackground(false); - curveListWidget->setFrameShape(QFrame::NoFrame); - curveListWidget->setFrameShadow(QFrame::Sunken); - curveListWidget->setWidgetResizable(true); - curveListWidget->setAlignment(Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop); - scrollAreaWidgetContents = new QWidget(); - scrollAreaWidgetContents->setObjectName(QString::fromUtf8("scrollAreaWidgetContents")); - scrollAreaWidgetContents->setGeometry(QRect(0, 0, 242, 361)); - curveListWidget->setWidget(scrollAreaWidgetContents); - - verticalLayout->addWidget(curveListWidget); - - - horizontalLayout_2->addWidget(curveGroupBox); - - diagramGroupBox = new QGroupBox(linechart); - diagramGroupBox->setObjectName(QString::fromUtf8("diagramGroupBox")); - QSizePolicy sizePolicy3(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); - sizePolicy3.setHorizontalStretch(9); - sizePolicy3.setVerticalStretch(0); - sizePolicy3.setHeightForWidth(diagramGroupBox->sizePolicy().hasHeightForWidth()); - diagramGroupBox->setSizePolicy(sizePolicy3); - diagramGroupBox->setMinimumSize(QSize(400, 300)); - diagramGroupBox->setBaseSize(QSize(800, 300)); - - horizontalLayout_2->addWidget(diagramGroupBox); - - - retranslateUi(linechart); - - QMetaObject::connectSlotsByName(linechart); - } // setupUi - - void retranslateUi(QWidget *linechart) { - linechart->setWindowTitle(QApplication::translate("linechart", "Form", 0, QApplication::UnicodeUTF8)); - curveGroupBox->setTitle(QApplication::translate("linechart", "Curve Selection", 0, QApplication::UnicodeUTF8)); - diagramGroupBox->setTitle(QApplication::translate("linechart", "Diagram", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class linechart: public Ui_linechart {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // LINECHART_H diff --git a/src/ui/generated/MAVLinkSettingsWidget.h b/src/ui/generated/MAVLinkSettingsWidget.h deleted file mode 100644 index a8681e4a667d07bec25d026abfbc63760a33f8d2..0000000000000000000000000000000000000000 --- a/src/ui/generated/MAVLinkSettingsWidget.h +++ /dev/null @@ -1,75 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'MAVLinkSettingsWidget.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef MAVLINKSETTINGSWIDGET_H -#define MAVLINKSETTINGSWIDGET_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_MAVLinkSettingsWidget -{ -public: - QVBoxLayout *verticalLayout; - QCheckBox *heartbeatCheckBox; - QCheckBox *loggingCheckBox; - QSpacerItem *verticalSpacer; - - void setupUi(QWidget *MAVLinkSettingsWidget) { - if (MAVLinkSettingsWidget->objectName().isEmpty()) - MAVLinkSettingsWidget->setObjectName(QString::fromUtf8("MAVLinkSettingsWidget")); - MAVLinkSettingsWidget->resize(267, 123); - verticalLayout = new QVBoxLayout(MAVLinkSettingsWidget); - verticalLayout->setContentsMargins(6, 6, 6, 6); - verticalLayout->setObjectName(QString::fromUtf8("verticalLayout")); - heartbeatCheckBox = new QCheckBox(MAVLinkSettingsWidget); - heartbeatCheckBox->setObjectName(QString::fromUtf8("heartbeatCheckBox")); - - verticalLayout->addWidget(heartbeatCheckBox); - - loggingCheckBox = new QCheckBox(MAVLinkSettingsWidget); - loggingCheckBox->setObjectName(QString::fromUtf8("loggingCheckBox")); - - verticalLayout->addWidget(loggingCheckBox); - - verticalSpacer = new QSpacerItem(20, 84, QSizePolicy::Minimum, QSizePolicy::Expanding); - - verticalLayout->addItem(verticalSpacer); - - - retranslateUi(MAVLinkSettingsWidget); - - QMetaObject::connectSlotsByName(MAVLinkSettingsWidget); - } // setupUi - - void retranslateUi(QWidget *MAVLinkSettingsWidget) { - MAVLinkSettingsWidget->setWindowTitle(QApplication::translate("MAVLinkSettingsWidget", "Form", 0, QApplication::UnicodeUTF8)); - heartbeatCheckBox->setText(QApplication::translate("MAVLinkSettingsWidget", "Emit heartbeat", 0, QApplication::UnicodeUTF8)); - loggingCheckBox->setText(QApplication::translate("MAVLinkSettingsWidget", "Log all MAVLink packets", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class MAVLinkSettingsWidget: public Ui_MAVLinkSettingsWidget {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // MAVLINKSETTINGSWIDGET_H diff --git a/src/ui/generated/MainWindow.h b/src/ui/generated/MainWindow.h deleted file mode 100644 index 4aaa634d148254d361daea139b648d6e465c0adb..0000000000000000000000000000000000000000 --- a/src/ui/generated/MainWindow.h +++ /dev/null @@ -1,8 +0,0 @@ -/**************************************************************************** -** Form interface generated from reading ui file 'src/ui/MainWindow.ui' -** -** Created: Tue Jun 1 20:21:32 2010 -** -** WARNING! All changes made in this file will be lost! -****************************************************************************/ - diff --git a/src/ui/generated/MapWidget.h b/src/ui/generated/MapWidget.h deleted file mode 100644 index a66d11c064c580aec4041593435a78e2a1413536..0000000000000000000000000000000000000000 --- a/src/ui/generated/MapWidget.h +++ /dev/null @@ -1,49 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'MapWidget.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef MAPWIDGET_H -#define MAPWIDGET_H - -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_MapWidget -{ -public: - - void setupUi(QWidget *MapWidget) { - if (MapWidget->objectName().isEmpty()) - MapWidget->setObjectName(QString::fromUtf8("MapWidget")); - MapWidget->resize(400, 300); - - retranslateUi(MapWidget); - - QMetaObject::connectSlotsByName(MapWidget); - } // setupUi - - void retranslateUi(QWidget *MapWidget) { - MapWidget->setWindowTitle(QApplication::translate("MapWidget", "Form", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class MapWidget: public Ui_MapWidget {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // MAPWIDGET_H diff --git a/src/ui/generated/ObjectDetectionView.h b/src/ui/generated/ObjectDetectionView.h deleted file mode 100644 index 2da502c1bcb6e9011dd2ff311251c8ffc4fa92e6..0000000000000000000000000000000000000000 --- a/src/ui/generated/ObjectDetectionView.h +++ /dev/null @@ -1,113 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'ObjectDetectionView.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef OBJECTDETECTIONVIEW_H -#define OBJECTDETECTIONVIEW_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_ObjectDetectionView -{ -public: - QGridLayout *gridLayout; - QListWidget *listWidget; - QListWidget *letterListWidget; - QLabel *imageLabel; - QLabel *letterLabel; - QLabel *nameLabel; - QPushButton *clearButton; - - void setupUi(QWidget *ObjectDetectionView) { - if (ObjectDetectionView->objectName().isEmpty()) - ObjectDetectionView->setObjectName(QString::fromUtf8("ObjectDetectionView")); - ObjectDetectionView->resize(246, 403); - gridLayout = new QGridLayout(ObjectDetectionView); - gridLayout->setObjectName(QString::fromUtf8("gridLayout")); - listWidget = new QListWidget(ObjectDetectionView); - listWidget->setObjectName(QString::fromUtf8("listWidget")); - - gridLayout->addWidget(listWidget, 0, 0, 1, 3); - - letterListWidget = new QListWidget(ObjectDetectionView); - letterListWidget->setObjectName(QString::fromUtf8("letterListWidget")); - - gridLayout->addWidget(letterListWidget, 1, 0, 1, 3); - - imageLabel = new QLabel(ObjectDetectionView); - imageLabel->setObjectName(QString::fromUtf8("imageLabel")); - QSizePolicy sizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred); - sizePolicy.setHorizontalStretch(10); - sizePolicy.setVerticalStretch(10); - sizePolicy.setHeightForWidth(imageLabel->sizePolicy().hasHeightForWidth()); - imageLabel->setSizePolicy(sizePolicy); - imageLabel->setMinimumSize(QSize(110, 110)); - imageLabel->setSizeIncrement(QSize(2, 2)); - imageLabel->setBaseSize(QSize(10, 10)); - - gridLayout->addWidget(imageLabel, 2, 0, 1, 1); - - letterLabel = new QLabel(ObjectDetectionView); - letterLabel->setObjectName(QString::fromUtf8("letterLabel")); - sizePolicy.setHeightForWidth(letterLabel->sizePolicy().hasHeightForWidth()); - letterLabel->setSizePolicy(sizePolicy); - letterLabel->setMinimumSize(QSize(110, 110)); - letterLabel->setSizeIncrement(QSize(2, 2)); - letterLabel->setBaseSize(QSize(10, 10)); - letterLabel->setStyleSheet(QString::fromUtf8("font: 72pt;\n" - "color: white;")); - letterLabel->setAlignment(Qt::AlignCenter); - - gridLayout->addWidget(letterLabel, 2, 1, 1, 2); - - nameLabel = new QLabel(ObjectDetectionView); - nameLabel->setObjectName(QString::fromUtf8("nameLabel")); - - gridLayout->addWidget(nameLabel, 3, 0, 1, 2); - - clearButton = new QPushButton(ObjectDetectionView); - clearButton->setObjectName(QString::fromUtf8("clearButton")); - clearButton->setMaximumSize(QSize(80, 16777215)); - - gridLayout->addWidget(clearButton, 3, 2, 1, 1); - - - retranslateUi(ObjectDetectionView); - - QMetaObject::connectSlotsByName(ObjectDetectionView); - } // setupUi - - void retranslateUi(QWidget *ObjectDetectionView) { - ObjectDetectionView->setWindowTitle(QApplication::translate("ObjectDetectionView", "Form", 0, QApplication::UnicodeUTF8)); - imageLabel->setText(QString()); - letterLabel->setText(QString()); - nameLabel->setText(QApplication::translate("ObjectDetectionView", "No objects recognized", 0, QApplication::UnicodeUTF8)); - clearButton->setText(QApplication::translate("ObjectDetectionView", "Clear", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class ObjectDetectionView: public Ui_ObjectDetectionView {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // OBJECTDETECTIONVIEW_H diff --git a/src/ui/generated/ParameterInterface.h b/src/ui/generated/ParameterInterface.h deleted file mode 100644 index d18431da26082c0aa8632efbac955c427e0d474b..0000000000000000000000000000000000000000 --- a/src/ui/generated/ParameterInterface.h +++ /dev/null @@ -1,120 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'ParameterInterface.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef PARAMETERINTERFACE_H -#define PARAMETERINTERFACE_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_parameterWidget -{ -public: - QGridLayout *gridLayout; - QLabel *label; - QComboBox *vehicleComboBox; - QGroupBox *groupBox_2; - QHBoxLayout *horizontalLayout; - QStackedWidget *stackedWidget; - QWidget *page; - QVBoxLayout *verticalLayout; - QWidget *page_2; - QStackedWidget *sensorSettings; - QWidget *page_3; - QVBoxLayout *verticalLayout_2; - QWidget *page_4; - - void setupUi(QWidget *parameterWidget) { - if (parameterWidget->objectName().isEmpty()) - parameterWidget->setObjectName(QString::fromUtf8("parameterWidget")); - parameterWidget->resize(350, 545); - gridLayout = new QGridLayout(parameterWidget); - gridLayout->setObjectName(QString::fromUtf8("gridLayout")); - label = new QLabel(parameterWidget); - label->setObjectName(QString::fromUtf8("label")); - - gridLayout->addWidget(label, 0, 0, 1, 1); - - vehicleComboBox = new QComboBox(parameterWidget); - vehicleComboBox->setObjectName(QString::fromUtf8("vehicleComboBox")); - - gridLayout->addWidget(vehicleComboBox, 0, 1, 1, 1); - - groupBox_2 = new QGroupBox(parameterWidget); - groupBox_2->setObjectName(QString::fromUtf8("groupBox_2")); - horizontalLayout = new QHBoxLayout(groupBox_2); - horizontalLayout->setObjectName(QString::fromUtf8("horizontalLayout")); - stackedWidget = new QStackedWidget(groupBox_2); - stackedWidget->setObjectName(QString::fromUtf8("stackedWidget")); - page = new QWidget(); - page->setObjectName(QString::fromUtf8("page")); - verticalLayout = new QVBoxLayout(page); - verticalLayout->setObjectName(QString::fromUtf8("verticalLayout")); - stackedWidget->addWidget(page); - page_2 = new QWidget(); - page_2->setObjectName(QString::fromUtf8("page_2")); - stackedWidget->addWidget(page_2); - - horizontalLayout->addWidget(stackedWidget); - - - gridLayout->addWidget(groupBox_2, 1, 0, 1, 2); - - sensorSettings = new QStackedWidget(parameterWidget); - sensorSettings->setObjectName(QString::fromUtf8("sensorSettings")); - page_3 = new QWidget(); - page_3->setObjectName(QString::fromUtf8("page_3")); - verticalLayout_2 = new QVBoxLayout(page_3); - verticalLayout_2->setObjectName(QString::fromUtf8("verticalLayout_2")); - sensorSettings->addWidget(page_3); - page_4 = new QWidget(); - page_4->setObjectName(QString::fromUtf8("page_4")); - sensorSettings->addWidget(page_4); - - gridLayout->addWidget(sensorSettings, 2, 0, 1, 2); - - - retranslateUi(parameterWidget); - - stackedWidget->setCurrentIndex(0); - sensorSettings->setCurrentIndex(0); - - - QMetaObject::connectSlotsByName(parameterWidget); - } // setupUi - - void retranslateUi(QWidget *parameterWidget) { - parameterWidget->setWindowTitle(QApplication::translate("parameterWidget", "Form", 0, QApplication::UnicodeUTF8)); - label->setText(QApplication::translate("parameterWidget", "Vehicle", 0, QApplication::UnicodeUTF8)); - groupBox_2->setTitle(QApplication::translate("parameterWidget", "Onboard Parameters", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class parameterWidget: public Ui_parameterWidget {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // PARAMETERINTERFACE_H diff --git a/src/ui/generated/QGCSensorSettingsWidget.h b/src/ui/generated/QGCSensorSettingsWidget.h deleted file mode 100644 index 96fa1bea6c50ca63c70df98b3ee6aac035d8172a..0000000000000000000000000000000000000000 --- a/src/ui/generated/QGCSensorSettingsWidget.h +++ /dev/null @@ -1,164 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'QGCSensorSettingsWidget.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef QGCSENSORSETTINGSWIDGET_H -#define QGCSENSORSETTINGSWIDGET_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_QGCSensorSettingsWidget -{ -public: - QGridLayout *gridLayout_4; - QGroupBox *groupBox; - QGridLayout *gridLayout_2; - QCheckBox *sendRawCheckBox; - QCheckBox *sendExtendedCheckBox; - QCheckBox *sendRCCheckBox; - QCheckBox *sendControllerCheckBox; - QCheckBox *sendPositionCheckBox; - QCheckBox *sendExtra1CheckBox; - QCheckBox *sendExtra2CheckBox; - QCheckBox *sendExtra3CheckBox; - QGroupBox *groupBox_3; - QGridLayout *gridLayout; - QPushButton *gyroCalButton; - QLabel *gyroCalDate; - QPushButton *magCalButton; - QLabel *magCalLabel; - - void setupUi(QWidget *QGCSensorSettingsWidget) { - if (QGCSensorSettingsWidget->objectName().isEmpty()) - QGCSensorSettingsWidget->setObjectName(QString::fromUtf8("QGCSensorSettingsWidget")); - QGCSensorSettingsWidget->resize(350, 545); - gridLayout_4 = new QGridLayout(QGCSensorSettingsWidget); - gridLayout_4->setContentsMargins(0, 0, 0, 0); - gridLayout_4->setObjectName(QString::fromUtf8("gridLayout_4")); - groupBox = new QGroupBox(QGCSensorSettingsWidget); - groupBox->setObjectName(QString::fromUtf8("groupBox")); - gridLayout_2 = new QGridLayout(groupBox); - gridLayout_2->setContentsMargins(6, 6, 6, 6); - gridLayout_2->setObjectName(QString::fromUtf8("gridLayout_2")); - sendRawCheckBox = new QCheckBox(groupBox); - sendRawCheckBox->setObjectName(QString::fromUtf8("sendRawCheckBox")); - - gridLayout_2->addWidget(sendRawCheckBox, 0, 0, 1, 1); - - sendExtendedCheckBox = new QCheckBox(groupBox); - sendExtendedCheckBox->setObjectName(QString::fromUtf8("sendExtendedCheckBox")); - - gridLayout_2->addWidget(sendExtendedCheckBox, 1, 0, 1, 1); - - sendRCCheckBox = new QCheckBox(groupBox); - sendRCCheckBox->setObjectName(QString::fromUtf8("sendRCCheckBox")); - - gridLayout_2->addWidget(sendRCCheckBox, 2, 0, 1, 1); - - sendControllerCheckBox = new QCheckBox(groupBox); - sendControllerCheckBox->setObjectName(QString::fromUtf8("sendControllerCheckBox")); - - gridLayout_2->addWidget(sendControllerCheckBox, 3, 0, 1, 1); - - sendPositionCheckBox = new QCheckBox(groupBox); - sendPositionCheckBox->setObjectName(QString::fromUtf8("sendPositionCheckBox")); - - gridLayout_2->addWidget(sendPositionCheckBox, 4, 0, 1, 1); - - sendExtra1CheckBox = new QCheckBox(groupBox); - sendExtra1CheckBox->setObjectName(QString::fromUtf8("sendExtra1CheckBox")); - - gridLayout_2->addWidget(sendExtra1CheckBox, 5, 0, 1, 1); - - sendExtra2CheckBox = new QCheckBox(groupBox); - sendExtra2CheckBox->setObjectName(QString::fromUtf8("sendExtra2CheckBox")); - - gridLayout_2->addWidget(sendExtra2CheckBox, 6, 0, 1, 1); - - sendExtra3CheckBox = new QCheckBox(groupBox); - sendExtra3CheckBox->setObjectName(QString::fromUtf8("sendExtra3CheckBox")); - - gridLayout_2->addWidget(sendExtra3CheckBox, 7, 0, 1, 1); - - - gridLayout_4->addWidget(groupBox, 0, 0, 1, 1); - - groupBox_3 = new QGroupBox(QGCSensorSettingsWidget); - groupBox_3->setObjectName(QString::fromUtf8("groupBox_3")); - gridLayout = new QGridLayout(groupBox_3); - gridLayout->setContentsMargins(6, 6, 6, 6); - gridLayout->setObjectName(QString::fromUtf8("gridLayout")); - gyroCalButton = new QPushButton(groupBox_3); - gyroCalButton->setObjectName(QString::fromUtf8("gyroCalButton")); - - gridLayout->addWidget(gyroCalButton, 0, 0, 1, 1); - - gyroCalDate = new QLabel(groupBox_3); - gyroCalDate->setObjectName(QString::fromUtf8("gyroCalDate")); - - gridLayout->addWidget(gyroCalDate, 0, 1, 1, 1); - - magCalButton = new QPushButton(groupBox_3); - magCalButton->setObjectName(QString::fromUtf8("magCalButton")); - - gridLayout->addWidget(magCalButton, 1, 0, 1, 1); - - magCalLabel = new QLabel(groupBox_3); - magCalLabel->setObjectName(QString::fromUtf8("magCalLabel")); - - gridLayout->addWidget(magCalLabel, 1, 1, 1, 1); - - - gridLayout_4->addWidget(groupBox_3, 1, 0, 1, 1); - - - retranslateUi(QGCSensorSettingsWidget); - - QMetaObject::connectSlotsByName(QGCSensorSettingsWidget); - } // setupUi - - void retranslateUi(QWidget *QGCSensorSettingsWidget) { - QGCSensorSettingsWidget->setWindowTitle(QApplication::translate("QGCSensorSettingsWidget", "Form", 0, QApplication::UnicodeUTF8)); - groupBox->setTitle(QApplication::translate("QGCSensorSettingsWidget", "Activate Extended Output", 0, QApplication::UnicodeUTF8)); - sendRawCheckBox->setText(QApplication::translate("QGCSensorSettingsWidget", "Send RAW Sensor data", 0, QApplication::UnicodeUTF8)); - sendExtendedCheckBox->setText(QApplication::translate("QGCSensorSettingsWidget", "Send extended status", 0, QApplication::UnicodeUTF8)); - sendRCCheckBox->setText(QApplication::translate("QGCSensorSettingsWidget", "Send RC-values", 0, QApplication::UnicodeUTF8)); - sendControllerCheckBox->setText(QApplication::translate("QGCSensorSettingsWidget", "Send raw controller outputs", 0, QApplication::UnicodeUTF8)); - sendPositionCheckBox->setText(QApplication::translate("QGCSensorSettingsWidget", "Send position setpoint and estimate", 0, QApplication::UnicodeUTF8)); - sendExtra1CheckBox->setText(QApplication::translate("QGCSensorSettingsWidget", "Send Extra1", 0, QApplication::UnicodeUTF8)); - sendExtra2CheckBox->setText(QApplication::translate("QGCSensorSettingsWidget", "Send Extra2", 0, QApplication::UnicodeUTF8)); - sendExtra3CheckBox->setText(QApplication::translate("QGCSensorSettingsWidget", "Send Extra3", 0, QApplication::UnicodeUTF8)); - groupBox_3->setTitle(QApplication::translate("QGCSensorSettingsWidget", "Calibration Wizards", 0, QApplication::UnicodeUTF8)); - gyroCalButton->setText(QApplication::translate("QGCSensorSettingsWidget", "Start dynamic calibration", 0, QApplication::UnicodeUTF8)); - gyroCalDate->setText(QApplication::translate("QGCSensorSettingsWidget", "Date unknown", 0, QApplication::UnicodeUTF8)); - magCalButton->setText(QApplication::translate("QGCSensorSettingsWidget", "Start static calibration", 0, QApplication::UnicodeUTF8)); - magCalLabel->setText(QApplication::translate("QGCSensorSettingsWidget", "Date unknown", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class QGCSensorSettingsWidget: public Ui_QGCSensorSettingsWidget {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // QGCSENSORSETTINGSWIDGET_H diff --git a/src/ui/generated/SerialSettings.h b/src/ui/generated/SerialSettings.h deleted file mode 100644 index df2ed91f7de2a9474f2d212d897ca776a8b25a6e..0000000000000000000000000000000000000000 --- a/src/ui/generated/SerialSettings.h +++ /dev/null @@ -1,8 +0,0 @@ -/**************************************************************************** -** Form interface generated from reading ui file 'src/ui/SerialSettings.ui' -** -** Created: Tue Jun 1 20:21:32 2010 -** -** WARNING! All changes made in this file will be lost! -****************************************************************************/ - diff --git a/src/ui/generated/UASControl.h b/src/ui/generated/UASControl.h deleted file mode 100644 index f9a8cdee31cc45f8c4d06798c91eff1eb0864e2b..0000000000000000000000000000000000000000 --- a/src/ui/generated/UASControl.h +++ /dev/null @@ -1,153 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'UASControl.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef UASCONTROL_H -#define UASCONTROL_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_uasControl -{ -public: - QGridLayout *gridLayout; - QLabel *controlStatusLabel; - QPushButton *controlButton; - QSpacerItem *verticalSpacer_2; - QSpacerItem *horizontalSpacer; - QPushButton *liftoffButton; - QPushButton *landButton; - QPushButton *shutdownButton; - QSpacerItem *horizontalSpacer_2; - QComboBox *modeComboBox; - QPushButton *setModeButton; - QLabel *lastActionLabel; - QSpacerItem *verticalSpacer; - - void setupUi(QWidget *uasControl) { - if (uasControl->objectName().isEmpty()) - uasControl->setObjectName(QString::fromUtf8("uasControl")); - uasControl->resize(280, 164); - uasControl->setMinimumSize(QSize(280, 130)); - gridLayout = new QGridLayout(uasControl); - gridLayout->setObjectName(QString::fromUtf8("gridLayout")); - gridLayout->setContentsMargins(6, 12, 6, 6); - controlStatusLabel = new QLabel(uasControl); - controlStatusLabel->setObjectName(QString::fromUtf8("controlStatusLabel")); - controlStatusLabel->setAlignment(Qt::AlignCenter); - - gridLayout->addWidget(controlStatusLabel, 0, 1, 1, 4); - - controlButton = new QPushButton(uasControl); - controlButton->setObjectName(QString::fromUtf8("controlButton")); - - gridLayout->addWidget(controlButton, 1, 1, 1, 4); - - verticalSpacer_2 = new QSpacerItem(20, 0, QSizePolicy::Minimum, QSizePolicy::MinimumExpanding); - - gridLayout->addItem(verticalSpacer_2, 2, 1, 1, 4); - - horizontalSpacer = new QSpacerItem(31, 159, QSizePolicy::Expanding, QSizePolicy::Minimum); - - gridLayout->addItem(horizontalSpacer, 0, 0, 6, 1); - - liftoffButton = new QPushButton(uasControl); - liftoffButton->setObjectName(QString::fromUtf8("liftoffButton")); - QIcon icon; - icon.addFile(QString::fromUtf8(":/files/images/control/launch.svg"), QSize(), QIcon::Normal, QIcon::Off); - liftoffButton->setIcon(icon); - - gridLayout->addWidget(liftoffButton, 3, 1, 1, 1); - - landButton = new QPushButton(uasControl); - landButton->setObjectName(QString::fromUtf8("landButton")); - QIcon icon1; - icon1.addFile(QString::fromUtf8(":/files/images/control/land.svg"), QSize(), QIcon::Normal, QIcon::Off); - landButton->setIcon(icon1); - - gridLayout->addWidget(landButton, 3, 2, 1, 2); - - shutdownButton = new QPushButton(uasControl); - shutdownButton->setObjectName(QString::fromUtf8("shutdownButton")); - QIcon icon2; - icon2.addFile(QString::fromUtf8(":/files/images/actions/system-log-out.svg"), QSize(), QIcon::Normal, QIcon::Off); - shutdownButton->setIcon(icon2); - - gridLayout->addWidget(shutdownButton, 3, 4, 1, 1); - - horizontalSpacer_2 = new QSpacerItem(30, 159, QSizePolicy::Expanding, QSizePolicy::Minimum); - - gridLayout->addItem(horizontalSpacer_2, 0, 5, 6, 1); - - modeComboBox = new QComboBox(uasControl); - modeComboBox->setObjectName(QString::fromUtf8("modeComboBox")); - - gridLayout->addWidget(modeComboBox, 4, 1, 1, 2); - - setModeButton = new QPushButton(uasControl); - setModeButton->setObjectName(QString::fromUtf8("setModeButton")); - QIcon icon3; - icon3.addFile(QString::fromUtf8(":/files/images/devices/network-wireless.svg"), QSize(), QIcon::Normal, QIcon::Off); - setModeButton->setIcon(icon3); - - gridLayout->addWidget(setModeButton, 4, 3, 1, 2); - - lastActionLabel = new QLabel(uasControl); - lastActionLabel->setObjectName(QString::fromUtf8("lastActionLabel")); - lastActionLabel->setAlignment(Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop); - - gridLayout->addWidget(lastActionLabel, 5, 1, 1, 4); - - verticalSpacer = new QSpacerItem(0, 1, QSizePolicy::Minimum, QSizePolicy::Expanding); - - gridLayout->addItem(verticalSpacer, 6, 0, 1, 6); - - gridLayout->setRowMinimumHeight(0, 5); - gridLayout->setRowMinimumHeight(1, 10); - gridLayout->setRowMinimumHeight(2, 10); - gridLayout->setRowMinimumHeight(4, 10); - gridLayout->setRowMinimumHeight(5, 5); - - retranslateUi(uasControl); - - QMetaObject::connectSlotsByName(uasControl); - } // setupUi - - void retranslateUi(QWidget *uasControl) { - uasControl->setWindowTitle(QApplication::translate("uasControl", "Form", 0, QApplication::UnicodeUTF8)); - controlStatusLabel->setText(QApplication::translate("uasControl", "UNCONNECTED", 0, QApplication::UnicodeUTF8)); - controlButton->setText(QApplication::translate("uasControl", "Activate Engine", 0, QApplication::UnicodeUTF8)); - liftoffButton->setText(QApplication::translate("uasControl", "Liftoff", 0, QApplication::UnicodeUTF8)); - landButton->setText(QApplication::translate("uasControl", "Land", 0, QApplication::UnicodeUTF8)); - shutdownButton->setText(QApplication::translate("uasControl", "Halt", 0, QApplication::UnicodeUTF8)); - setModeButton->setText(QApplication::translate("uasControl", "Set Mode", 0, QApplication::UnicodeUTF8)); - lastActionLabel->setText(QApplication::translate("uasControl", "No actions executed so far", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class uasControl: public Ui_uasControl {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // UASCONTROL_H diff --git a/src/ui/generated/UASInfo.h b/src/ui/generated/UASInfo.h deleted file mode 100644 index ebb7bfd7527d45f230cc665d7d01f22f5353014d..0000000000000000000000000000000000000000 --- a/src/ui/generated/UASInfo.h +++ /dev/null @@ -1,296 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'UASInfo.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef UASINFO_H -#define UASINFO_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_uasInfo -{ -public: - QGridLayout *gridLayout; - QLabel *label; - QSpacerItem *horizontalSpacer_2; - QLabel *voltageLabel; - QLabel *label_7; - QProgressBar *batteryBar; - QLabel *label_2; - QSpacerItem *horizontalSpacer_3; - QLabel *receiveLossLabel; - QLabel *label_8; - QProgressBar *receiveLossBar; - QLabel *label_6; - QSpacerItem *horizontalSpacer_9; - QLabel *sendLossLabel; - QLabel *label_11; - QProgressBar *sendLossBar; - QLabel *label_3; - QSpacerItem *horizontalSpacer_4; - QLabel *loadLabel; - QLabel *label_9; - QProgressBar *loadBar; - QFrame *line; - QSpacerItem *verticalSpacer; - QLabel *errorLabel; - QLabel *label_4; - QLabel *label_5; - QLabel *label_10; - QProgressBar *progressBar; - QSpacerItem *horizontalSpacer; - - void setupUi(QWidget *uasInfo) { - if (uasInfo->objectName().isEmpty()) - uasInfo->setObjectName(QString::fromUtf8("uasInfo")); - uasInfo->resize(455, 220); - uasInfo->setStyleSheet(QString::fromUtf8("")); - gridLayout = new QGridLayout(uasInfo); - gridLayout->setContentsMargins(6, 6, 6, 6); - gridLayout->setObjectName(QString::fromUtf8("gridLayout")); - label = new QLabel(uasInfo); - label->setObjectName(QString::fromUtf8("label")); - - gridLayout->addWidget(label, 0, 0, 1, 1); - - horizontalSpacer_2 = new QSpacerItem(13, 15, QSizePolicy::Maximum, QSizePolicy::Minimum); - - gridLayout->addItem(horizontalSpacer_2, 0, 1, 1, 1); - - voltageLabel = new QLabel(uasInfo); - voltageLabel->setObjectName(QString::fromUtf8("voltageLabel")); - voltageLabel->setTextFormat(Qt::AutoText); - voltageLabel->setAlignment(Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter); - - gridLayout->addWidget(voltageLabel, 0, 2, 1, 1); - - label_7 = new QLabel(uasInfo); - label_7->setObjectName(QString::fromUtf8("label_7")); - label_7->setTextFormat(Qt::AutoText); - label_7->setAlignment(Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter); - - gridLayout->addWidget(label_7, 0, 3, 1, 1); - - batteryBar = new QProgressBar(uasInfo); - batteryBar->setObjectName(QString::fromUtf8("batteryBar")); - QSizePolicy sizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::Fixed); - sizePolicy.setHorizontalStretch(10); - sizePolicy.setVerticalStretch(18); - sizePolicy.setHeightForWidth(batteryBar->sizePolicy().hasHeightForWidth()); - batteryBar->setSizePolicy(sizePolicy); - batteryBar->setMinimumSize(QSize(100, 0)); - batteryBar->setMaximumSize(QSize(16777215, 20)); - batteryBar->setBaseSize(QSize(0, 18)); - batteryBar->setMinimum(0); - batteryBar->setMaximum(100); - batteryBar->setValue(80); - batteryBar->setTextVisible(true); - - gridLayout->addWidget(batteryBar, 0, 4, 1, 2); - - label_2 = new QLabel(uasInfo); - label_2->setObjectName(QString::fromUtf8("label_2")); - - gridLayout->addWidget(label_2, 1, 0, 1, 1); - - horizontalSpacer_3 = new QSpacerItem(13, 15, QSizePolicy::Maximum, QSizePolicy::Minimum); - - gridLayout->addItem(horizontalSpacer_3, 1, 1, 1, 1); - - receiveLossLabel = new QLabel(uasInfo); - receiveLossLabel->setObjectName(QString::fromUtf8("receiveLossLabel")); - receiveLossLabel->setTextFormat(Qt::AutoText); - receiveLossLabel->setAlignment(Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter); - - gridLayout->addWidget(receiveLossLabel, 1, 2, 1, 1); - - label_8 = new QLabel(uasInfo); - label_8->setObjectName(QString::fromUtf8("label_8")); - label_8->setTextFormat(Qt::AutoText); - label_8->setAlignment(Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter); - - gridLayout->addWidget(label_8, 1, 3, 1, 1); - - receiveLossBar = new QProgressBar(uasInfo); - receiveLossBar->setObjectName(QString::fromUtf8("receiveLossBar")); - sizePolicy.setHeightForWidth(receiveLossBar->sizePolicy().hasHeightForWidth()); - receiveLossBar->setSizePolicy(sizePolicy); - receiveLossBar->setMinimumSize(QSize(100, 0)); - receiveLossBar->setMaximumSize(QSize(16777215, 20)); - receiveLossBar->setBaseSize(QSize(0, 18)); - receiveLossBar->setValue(0); - receiveLossBar->setTextVisible(true); - - gridLayout->addWidget(receiveLossBar, 1, 4, 1, 2); - - label_6 = new QLabel(uasInfo); - label_6->setObjectName(QString::fromUtf8("label_6")); - - gridLayout->addWidget(label_6, 2, 0, 1, 1); - - horizontalSpacer_9 = new QSpacerItem(13, 15, QSizePolicy::Maximum, QSizePolicy::Minimum); - - gridLayout->addItem(horizontalSpacer_9, 2, 1, 1, 1); - - sendLossLabel = new QLabel(uasInfo); - sendLossLabel->setObjectName(QString::fromUtf8("sendLossLabel")); - sendLossLabel->setTextFormat(Qt::AutoText); - sendLossLabel->setAlignment(Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter); - - gridLayout->addWidget(sendLossLabel, 2, 2, 1, 1); - - label_11 = new QLabel(uasInfo); - label_11->setObjectName(QString::fromUtf8("label_11")); - label_11->setTextFormat(Qt::AutoText); - label_11->setAlignment(Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter); - - gridLayout->addWidget(label_11, 2, 3, 1, 1); - - sendLossBar = new QProgressBar(uasInfo); - sendLossBar->setObjectName(QString::fromUtf8("sendLossBar")); - sizePolicy.setHeightForWidth(sendLossBar->sizePolicy().hasHeightForWidth()); - sendLossBar->setSizePolicy(sizePolicy); - sendLossBar->setMinimumSize(QSize(100, 0)); - sendLossBar->setMaximumSize(QSize(16777215, 20)); - sendLossBar->setBaseSize(QSize(0, 18)); - sendLossBar->setValue(0); - sendLossBar->setTextVisible(true); - - gridLayout->addWidget(sendLossBar, 2, 4, 1, 2); - - label_3 = new QLabel(uasInfo); - label_3->setObjectName(QString::fromUtf8("label_3")); - - gridLayout->addWidget(label_3, 3, 0, 1, 1); - - horizontalSpacer_4 = new QSpacerItem(13, 15, QSizePolicy::Maximum, QSizePolicy::Minimum); - - gridLayout->addItem(horizontalSpacer_4, 3, 1, 1, 1); - - loadLabel = new QLabel(uasInfo); - loadLabel->setObjectName(QString::fromUtf8("loadLabel")); - loadLabel->setTextFormat(Qt::AutoText); - loadLabel->setAlignment(Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter); - - gridLayout->addWidget(loadLabel, 3, 2, 1, 1); - - label_9 = new QLabel(uasInfo); - label_9->setObjectName(QString::fromUtf8("label_9")); - label_9->setTextFormat(Qt::AutoText); - label_9->setAlignment(Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter); - - gridLayout->addWidget(label_9, 3, 3, 1, 1); - - loadBar = new QProgressBar(uasInfo); - loadBar->setObjectName(QString::fromUtf8("loadBar")); - sizePolicy.setHeightForWidth(loadBar->sizePolicy().hasHeightForWidth()); - loadBar->setSizePolicy(sizePolicy); - loadBar->setMinimumSize(QSize(100, 0)); - loadBar->setMaximumSize(QSize(16777215, 20)); - loadBar->setBaseSize(QSize(0, 18)); - loadBar->setValue(24); - loadBar->setTextVisible(true); - - gridLayout->addWidget(loadBar, 3, 4, 1, 2); - - line = new QFrame(uasInfo); - line->setObjectName(QString::fromUtf8("line")); - line->setFrameShape(QFrame::HLine); - line->setFrameShadow(QFrame::Sunken); - - gridLayout->addWidget(line, 5, 0, 1, 6); - - verticalSpacer = new QSpacerItem(0, 0, QSizePolicy::Minimum, QSizePolicy::Expanding); - - gridLayout->addItem(verticalSpacer, 7, 0, 1, 7); - - errorLabel = new QLabel(uasInfo); - errorLabel->setObjectName(QString::fromUtf8("errorLabel")); - - gridLayout->addWidget(errorLabel, 6, 0, 1, 6); - - label_4 = new QLabel(uasInfo); - label_4->setObjectName(QString::fromUtf8("label_4")); - - gridLayout->addWidget(label_4, 4, 0, 1, 1); - - label_5 = new QLabel(uasInfo); - label_5->setObjectName(QString::fromUtf8("label_5")); - label_5->setAlignment(Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter); - - gridLayout->addWidget(label_5, 4, 2, 1, 1); - - label_10 = new QLabel(uasInfo); - label_10->setObjectName(QString::fromUtf8("label_10")); - - gridLayout->addWidget(label_10, 4, 3, 1, 1); - - progressBar = new QProgressBar(uasInfo); - progressBar->setObjectName(QString::fromUtf8("progressBar")); - progressBar->setMaximumSize(QSize(16777215, 20)); - progressBar->setBaseSize(QSize(0, 18)); - progressBar->setValue(24); - - gridLayout->addWidget(progressBar, 4, 4, 1, 2); - - horizontalSpacer = new QSpacerItem(13, 15, QSizePolicy::Expanding, QSizePolicy::Minimum); - - gridLayout->addItem(horizontalSpacer, 4, 1, 1, 1); - - - retranslateUi(uasInfo); - - QMetaObject::connectSlotsByName(uasInfo); - } // setupUi - - void retranslateUi(QWidget *uasInfo) { - uasInfo->setWindowTitle(QApplication::translate("uasInfo", "Form", 0, QApplication::UnicodeUTF8)); - label->setText(QApplication::translate("uasInfo", "Battery", 0, QApplication::UnicodeUTF8)); - voltageLabel->setText(QApplication::translate("uasInfo", "12", 0, QApplication::UnicodeUTF8)); - label_7->setText(QApplication::translate("uasInfo", "V", 0, QApplication::UnicodeUTF8)); - batteryBar->setFormat(QApplication::translate("uasInfo", "%p%", 0, QApplication::UnicodeUTF8)); - label_2->setText(QApplication::translate("uasInfo", "Recv. Loss", 0, QApplication::UnicodeUTF8)); - receiveLossLabel->setText(QApplication::translate("uasInfo", "0", 0, QApplication::UnicodeUTF8)); - label_8->setText(QApplication::translate("uasInfo", "%", 0, QApplication::UnicodeUTF8)); - receiveLossBar->setFormat(QApplication::translate("uasInfo", "%p%", 0, QApplication::UnicodeUTF8)); - label_6->setText(QApplication::translate("uasInfo", "Send Loss", 0, QApplication::UnicodeUTF8)); - sendLossLabel->setText(QApplication::translate("uasInfo", "0", 0, QApplication::UnicodeUTF8)); - label_11->setText(QApplication::translate("uasInfo", "%", 0, QApplication::UnicodeUTF8)); - sendLossBar->setFormat(QApplication::translate("uasInfo", "%p%", 0, QApplication::UnicodeUTF8)); - label_3->setText(QApplication::translate("uasInfo", "MCU Load", 0, QApplication::UnicodeUTF8)); - loadLabel->setText(QApplication::translate("uasInfo", "0", 0, QApplication::UnicodeUTF8)); - label_9->setText(QApplication::translate("uasInfo", "%", 0, QApplication::UnicodeUTF8)); - loadBar->setFormat(QApplication::translate("uasInfo", "%p%", 0, QApplication::UnicodeUTF8)); - errorLabel->setText(QApplication::translate("uasInfo", "No error status received yet", 0, QApplication::UnicodeUTF8)); - label_4->setText(QApplication::translate("uasInfo", "CPU Load", 0, QApplication::UnicodeUTF8)); - label_5->setText(QApplication::translate("uasInfo", "0", 0, QApplication::UnicodeUTF8)); - label_10->setText(QApplication::translate("uasInfo", "%", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class uasInfo: public Ui_uasInfo {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // UASINFO_H diff --git a/src/ui/generated/UASList.h b/src/ui/generated/UASList.h deleted file mode 100644 index 63a00af52f007dba290dbd45b56edf1d75ab3a1c..0000000000000000000000000000000000000000 --- a/src/ui/generated/UASList.h +++ /dev/null @@ -1,50 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'UASList.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef UASLIST_H -#define UASLIST_H - -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_UASList -{ -public: - - void setupUi(QWidget *UASList) { - if (UASList->objectName().isEmpty()) - UASList->setObjectName(QString::fromUtf8("UASList")); - UASList->resize(400, 300); - UASList->setMinimumSize(QSize(500, 0)); - - retranslateUi(UASList); - - QMetaObject::connectSlotsByName(UASList); - } // setupUi - - void retranslateUi(QWidget *UASList) { - UASList->setWindowTitle(QApplication::translate("UASList", "Form", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class UASList: public Ui_UASList {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // UASLIST_H diff --git a/src/ui/generated/UASView.h b/src/ui/generated/UASView.h deleted file mode 100644 index a30ece7c2dcf6eda37fe6fdc56cdbb6eb3f12e5c..0000000000000000000000000000000000000000 --- a/src/ui/generated/UASView.h +++ /dev/null @@ -1,491 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'UASView.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef UASVIEW_H -#define UASVIEW_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_UASView -{ -public: - QHBoxLayout *horizontalLayout_2; - QGroupBox *uasViewFrame; - QGridLayout *gridLayout; - QToolButton *typeButton; - QSpacerItem *horizontalSpacer_2; - QLabel *nameLabel; - QLabel *modeLabel; - QLabel *timeRemainingLabel; - QLabel *timeElapsedLabel; - QProgressBar *thrustBar; - QLabel *groundDistanceLabel; - QLabel *speedLabel; - QGroupBox *heartbeatIcon; - QProgressBar *batteryBar; - QLabel *stateLabel; - QLabel *waypointLabel; - QLabel *positionLabel; - QLabel *gpsLabel; - QLabel *statusTextLabel; - QHBoxLayout *horizontalLayout; - QPushButton *liftoffButton; - QPushButton *haltButton; - QPushButton *continueButton; - QPushButton *landButton; - QPushButton *shutdownButton; - QPushButton *abortButton; - QPushButton *killButton; - - void setupUi(QWidget *UASView) { - if (UASView->objectName().isEmpty()) - UASView->setObjectName(QString::fromUtf8("UASView")); - UASView->resize(362, 120); - QSizePolicy sizePolicy(QSizePolicy::Maximum, QSizePolicy::Fixed); - sizePolicy.setHorizontalStretch(0); - sizePolicy.setVerticalStretch(0); - sizePolicy.setHeightForWidth(UASView->sizePolicy().hasHeightForWidth()); - UASView->setSizePolicy(sizePolicy); - UASView->setMinimumSize(QSize(0, 0)); - UASView->setStyleSheet(QString::fromUtf8("QWidget#colorIcon {}\n" - "\n" - "QWidget {\n" - "background-color: none;\n" - "color: #DDDDDF;\n" - "border-color: #EEEEEE;\n" - "background-clip: margin;\n" - "}\n" - "\n" - "QLabel#nameLabel {\n" - " font: bold 16px;\n" - " color: #3C7B9E;\n" - "}\n" - "\n" - "QLabel#modeLabel {\n" - " font: 12px;\n" - "}\n" - "\n" - "QLabel#stateLabel {\n" - " font: 12px;\n" - "}\n" - "\n" - "QLabel#gpsLabel {\n" - " font: 8px;\n" - "}\n" - "\n" - "QLabel#positionLabel {\n" - " font: 8px;\n" - "}\n" - "\n" - "QLabel#timeElapsedLabel {\n" - " font: 8px;\n" - "}\n" - "\n" - "QLabel#groundDistanceLabel {\n" - " font: 8px;\n" - "}\n" - "\n" - "QLabel#speedLabel {\n" - " font: 8px;\n" - "}\n" - "\n" - "QLabel#timeRemainingLabel {\n" - " font: 8px;\n" - "}\n" - "\n" - "QLabel#waypointLabel {\n" - " font: 24px;\n" - "}\n" - "\n" - "QGroupBox {\n" - " border: 1px solid #4A4A4F;\n" - " border-radius: 5px;\n" - " padding: 0px 0px 0px 0px;\n" - " margin: 0px;\n" - "}\n" - "\n" - " QGroupBox::title {\n" - " subcontrol-origin: margin;\n" - " subcontrol-position: top center; /* position at the top center */\n" - " margin: 0 3px 0px 3px;\n" - " " - " padding: 0 3px 0px 0px;\n" - " font: bold 8px;\n" - " }\n" - "\n" - "QGroupBox#heartbeatIcon {\n" - " background-color: red;\n" - "}\n" - "\n" - "QToolButton#typeButton {\n" - " font-weight: bold;\n" - " font-size: 12px;\n" - " border: 2px solid #999999;\n" - " border-radius: 5px;\n" - " min-width:44px;\n" - " max-width: 44px;\n" - " min-height: 44px;\n" - " max-height: 44px;\n" - " padding: 0px;\n" - " background-color: none;\n" - "}\n" - "\n" - "QPushButton {\n" - " font-weight: bold;\n" - " font-size: 12px;\n" - " border: 1px solid #999999;\n" - " border-radius: 10px;\n" - " min-width: 20px;\n" - " max-width: 40px;\n" - " min-height: 16px;\n" - " max-height: 16px;\n" - " padding: 2px;\n" - " background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #777777, stop: 1 #555555);\n" - "}\n" - "\n" - "QPushButton:pressed {\n" - " background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #444444, stop: 1 #555555);\n" - "}\n" - "\n" - "QPushButton#abortButton {\n" - " background: qlineargradient(x1:0, y1:0, x2:0, y2:1,\n" - " stop:0 #" - "ffee01, stop:1 #ae8f00);\n" - "}\n" - "\n" - "QPushButton:pressed#abortButton {\n" - " background: qlineargradient(x1:0, y1:0, x2:0, y2:1,\n" - " stop:0 #bbaa00, stop:1 #a05b00);\n" - "}\n" - "\n" - "QPushButton#killButton {\n" - " background: qlineargradient(x1:0, y1:0, x2:0, y2:1,\n" - " stop:0 #ffb917, stop:1 #b37300);\n" - "}\n" - "\n" - "QPushButton:pressed#killButton {\n" - " background: qlineargradient(x1:0, y1:0, x2:0, y2:1,\n" - " stop:0 #bb8500, stop:1 #903000);\n" - "}\n" - "\n" - "\n" - "QProgressBar {\n" - " border: 1px solid #4A4A4F;\n" - " border-radius: 4px;\n" - " text-align: center;\n" - " padding: 2px;\n" - " color: #DDDDDF;\n" - " background-color: #111118;\n" - "}\n" - "\n" - "QProgressBar:horizontal {\n" - " height: 10px;\n" - "}\n" - "\n" - "QProgressBar QLabel {\n" - " font-size: 8px;\n" - "}\n" - "\n" - "QProgressBar:vertical {\n" - " width: 12px;\n" - "}\n" - "\n" - "QProgressBar::chunk {\n" - " background-color: #656565;\n" - "}\n" - "\n" - "QProgressBar::chunk#batteryBar {\n" - " backgrou" - "nd-color: green;\n" - "}\n" - "\n" - "QProgressBar::chunk#speedBar {\n" - " background-color: yellow;\n" - "}\n" - "\n" - "QProgressBar::chunk#thrustBar {\n" - " background-color: orange;\n" - "}")); - horizontalLayout_2 = new QHBoxLayout(UASView); - horizontalLayout_2->setContentsMargins(6, 6, 6, 6); - horizontalLayout_2->setObjectName(QString::fromUtf8("horizontalLayout_2")); - uasViewFrame = new QGroupBox(UASView); - uasViewFrame->setObjectName(QString::fromUtf8("uasViewFrame")); - QSizePolicy sizePolicy1(QSizePolicy::MinimumExpanding, QSizePolicy::Fixed); - sizePolicy1.setHorizontalStretch(0); - sizePolicy1.setVerticalStretch(0); - sizePolicy1.setHeightForWidth(uasViewFrame->sizePolicy().hasHeightForWidth()); - uasViewFrame->setSizePolicy(sizePolicy1); - uasViewFrame->setMinimumSize(QSize(0, 0)); - gridLayout = new QGridLayout(uasViewFrame); - gridLayout->setContentsMargins(6, 6, 6, 6); - gridLayout->setObjectName(QString::fromUtf8("gridLayout")); - gridLayout->setHorizontalSpacing(6); - gridLayout->setVerticalSpacing(2); - typeButton = new QToolButton(uasViewFrame); - typeButton->setObjectName(QString::fromUtf8("typeButton")); - typeButton->setMinimumSize(QSize(48, 48)); - typeButton->setMaximumSize(QSize(48, 48)); - typeButton->setBaseSize(QSize(30, 30)); - QIcon icon; - icon.addFile(QString::fromUtf8(":/files/images/mavs/unknown.svg"), QSize(), QIcon::Normal, QIcon::Off); - typeButton->setIcon(icon); - typeButton->setIconSize(QSize(42, 42)); - - gridLayout->addWidget(typeButton, 0, 0, 5, 2); - - horizontalSpacer_2 = new QSpacerItem(6, 88, QSizePolicy::Expanding, QSizePolicy::Minimum); - - gridLayout->addItem(horizontalSpacer_2, 0, 2, 8, 1); - - nameLabel = new QLabel(uasViewFrame); - nameLabel->setObjectName(QString::fromUtf8("nameLabel")); - nameLabel->setMaximumSize(QSize(16777215, 16)); - QFont font; - font.setBold(true); - font.setItalic(false); - font.setWeight(75); - nameLabel->setFont(font); - - gridLayout->addWidget(nameLabel, 0, 3, 1, 3); - - modeLabel = new QLabel(uasViewFrame); - modeLabel->setObjectName(QString::fromUtf8("modeLabel")); - modeLabel->setMaximumSize(QSize(16777215, 16)); - QFont font1; - font1.setBold(false); - font1.setItalic(false); - font1.setWeight(50); - modeLabel->setFont(font1); - - gridLayout->addWidget(modeLabel, 0, 6, 1, 2); - - timeRemainingLabel = new QLabel(uasViewFrame); - timeRemainingLabel->setObjectName(QString::fromUtf8("timeRemainingLabel")); - timeRemainingLabel->setFont(font1); - - gridLayout->addWidget(timeRemainingLabel, 1, 3, 3, 1); - - timeElapsedLabel = new QLabel(uasViewFrame); - timeElapsedLabel->setObjectName(QString::fromUtf8("timeElapsedLabel")); - timeElapsedLabel->setFont(font1); - - gridLayout->addWidget(timeElapsedLabel, 1, 4, 3, 2); - - thrustBar = new QProgressBar(uasViewFrame); - thrustBar->setObjectName(QString::fromUtf8("thrustBar")); - QFont font2; - font2.setPointSize(8); - thrustBar->setFont(font2); - thrustBar->setValue(0); - - gridLayout->addWidget(thrustBar, 3, 6, 2, 2); - - groundDistanceLabel = new QLabel(uasViewFrame); - groundDistanceLabel->setObjectName(QString::fromUtf8("groundDistanceLabel")); - groundDistanceLabel->setFont(font1); - - gridLayout->addWidget(groundDistanceLabel, 4, 3, 1, 1); - - speedLabel = new QLabel(uasViewFrame); - speedLabel->setObjectName(QString::fromUtf8("speedLabel")); - speedLabel->setFont(font1); - - gridLayout->addWidget(speedLabel, 4, 4, 1, 2); - - heartbeatIcon = new QGroupBox(uasViewFrame); - heartbeatIcon->setObjectName(QString::fromUtf8("heartbeatIcon")); - QSizePolicy sizePolicy2(QSizePolicy::Fixed, QSizePolicy::Preferred); - sizePolicy2.setHorizontalStretch(0); - sizePolicy2.setVerticalStretch(0); - sizePolicy2.setHeightForWidth(heartbeatIcon->sizePolicy().hasHeightForWidth()); - heartbeatIcon->setSizePolicy(sizePolicy2); - heartbeatIcon->setMinimumSize(QSize(18, 0)); - heartbeatIcon->setMaximumSize(QSize(18, 40)); - - gridLayout->addWidget(heartbeatIcon, 5, 0, 3, 1); - - batteryBar = new QProgressBar(uasViewFrame); - batteryBar->setObjectName(QString::fromUtf8("batteryBar")); - batteryBar->setMinimumSize(QSize(18, 0)); - batteryBar->setMaximumSize(QSize(18, 40)); - QFont font3; - font3.setPointSize(6); - batteryBar->setFont(font3); - batteryBar->setValue(0); - batteryBar->setOrientation(Qt::Vertical); - - gridLayout->addWidget(batteryBar, 5, 1, 3, 1); - - stateLabel = new QLabel(uasViewFrame); - stateLabel->setObjectName(QString::fromUtf8("stateLabel")); - stateLabel->setFont(font1); - - gridLayout->addWidget(stateLabel, 5, 3, 2, 2); - - waypointLabel = new QLabel(uasViewFrame); - waypointLabel->setObjectName(QString::fromUtf8("waypointLabel")); - waypointLabel->setFont(font1); - waypointLabel->setAlignment(Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop); - - gridLayout->addWidget(waypointLabel, 7, 3, 1, 2); - - positionLabel = new QLabel(uasViewFrame); - positionLabel->setObjectName(QString::fromUtf8("positionLabel")); - positionLabel->setMinimumSize(QSize(0, 12)); - positionLabel->setMaximumSize(QSize(16777215, 12)); - positionLabel->setFont(font1); - - gridLayout->addWidget(positionLabel, 2, 6, 1, 1); - - gpsLabel = new QLabel(uasViewFrame); - gpsLabel->setObjectName(QString::fromUtf8("gpsLabel")); - gpsLabel->setMinimumSize(QSize(0, 12)); - gpsLabel->setMaximumSize(QSize(16777215, 12)); - gpsLabel->setFont(font1); - - gridLayout->addWidget(gpsLabel, 2, 7, 1, 1); - - statusTextLabel = new QLabel(uasViewFrame); - statusTextLabel->setObjectName(QString::fromUtf8("statusTextLabel")); - statusTextLabel->setMaximumSize(QSize(16777215, 12)); - QFont font4; - font4.setPointSize(10); - statusTextLabel->setFont(font4); - - gridLayout->addWidget(statusTextLabel, 5, 6, 1, 2); - - horizontalLayout = new QHBoxLayout(); - horizontalLayout->setSpacing(4); - horizontalLayout->setObjectName(QString::fromUtf8("horizontalLayout")); - horizontalLayout->setSizeConstraint(QLayout::SetMinimumSize); - liftoffButton = new QPushButton(uasViewFrame); - liftoffButton->setObjectName(QString::fromUtf8("liftoffButton")); - liftoffButton->setMinimumSize(QSize(26, 22)); - QIcon icon1; - icon1.addFile(QString::fromUtf8(":/files/images/control/launch.svg"), QSize(), QIcon::Normal, QIcon::Off); - liftoffButton->setIcon(icon1); - - horizontalLayout->addWidget(liftoffButton); - - haltButton = new QPushButton(uasViewFrame); - haltButton->setObjectName(QString::fromUtf8("haltButton")); - haltButton->setMinimumSize(QSize(26, 22)); - QIcon icon2; - icon2.addFile(QString::fromUtf8(":/files/images/actions/media-playback-pause.svg"), QSize(), QIcon::Normal, QIcon::Off); - haltButton->setIcon(icon2); - - horizontalLayout->addWidget(haltButton); - - continueButton = new QPushButton(uasViewFrame); - continueButton->setObjectName(QString::fromUtf8("continueButton")); - continueButton->setMinimumSize(QSize(26, 22)); - QIcon icon3; - icon3.addFile(QString::fromUtf8(":/files/images/actions/media-playback-start.svg"), QSize(), QIcon::Normal, QIcon::Off); - continueButton->setIcon(icon3); - - horizontalLayout->addWidget(continueButton); - - landButton = new QPushButton(uasViewFrame); - landButton->setObjectName(QString::fromUtf8("landButton")); - landButton->setMinimumSize(QSize(26, 22)); - QIcon icon4; - icon4.addFile(QString::fromUtf8(":/files/images/control/land.svg"), QSize(), QIcon::Normal, QIcon::Off); - landButton->setIcon(icon4); - - horizontalLayout->addWidget(landButton); - - shutdownButton = new QPushButton(uasViewFrame); - shutdownButton->setObjectName(QString::fromUtf8("shutdownButton")); - QIcon icon5; - icon5.addFile(QString::fromUtf8(":/files/images/actions/system-log-out.svg"), QSize(), QIcon::Normal, QIcon::Off); - shutdownButton->setIcon(icon5); - - horizontalLayout->addWidget(shutdownButton); - - abortButton = new QPushButton(uasViewFrame); - abortButton->setObjectName(QString::fromUtf8("abortButton")); - abortButton->setMinimumSize(QSize(26, 22)); - QIcon icon6; - icon6.addFile(QString::fromUtf8(":/files/images/actions/media-playback-stop.svg"), QSize(), QIcon::Normal, QIcon::Off); - abortButton->setIcon(icon6); - - horizontalLayout->addWidget(abortButton); - - killButton = new QPushButton(uasViewFrame); - killButton->setObjectName(QString::fromUtf8("killButton")); - killButton->setMinimumSize(QSize(26, 22)); - QIcon icon7; - icon7.addFile(QString::fromUtf8(":/files/images/actions/process-stop.svg"), QSize(), QIcon::Normal, QIcon::Off); - killButton->setIcon(icon7); - - horizontalLayout->addWidget(killButton); - - - gridLayout->addLayout(horizontalLayout, 6, 5, 2, 3); - - - horizontalLayout_2->addWidget(uasViewFrame); - - - retranslateUi(UASView); - - QMetaObject::connectSlotsByName(UASView); - } // setupUi - - void retranslateUi(QWidget *UASView) { - UASView->setWindowTitle(QApplication::translate("UASView", "Form", 0, QApplication::UnicodeUTF8)); - uasViewFrame->setTitle(QString()); - typeButton->setText(QApplication::translate("UASView", "...", 0, QApplication::UnicodeUTF8)); - nameLabel->setText(QApplication::translate("UASView", "UAS001", 0, QApplication::UnicodeUTF8)); - modeLabel->setText(QApplication::translate("UASView", "Waiting for first update..", 0, QApplication::UnicodeUTF8)); - timeRemainingLabel->setText(QApplication::translate("UASView", "00:00:00", 0, QApplication::UnicodeUTF8)); - timeElapsedLabel->setText(QApplication::translate("UASView", "00:00:00", 0, QApplication::UnicodeUTF8)); - groundDistanceLabel->setText(QApplication::translate("UASView", "00.00 m", 0, QApplication::UnicodeUTF8)); - speedLabel->setText(QApplication::translate("UASView", "00.0 m/s", 0, QApplication::UnicodeUTF8)); - heartbeatIcon->setTitle(QString()); - stateLabel->setText(QApplication::translate("UASView", "UNINIT", 0, QApplication::UnicodeUTF8)); - waypointLabel->setText(QApplication::translate("UASView", "WPX", 0, QApplication::UnicodeUTF8)); - positionLabel->setText(QApplication::translate("UASView", "00.0 00.0 00.0 m", 0, QApplication::UnicodeUTF8)); - gpsLabel->setText(QApplication::translate("UASView", "00 00 00 N 00 00 00 E", 0, QApplication::UnicodeUTF8)); - statusTextLabel->setText(QApplication::translate("UASView", "Unknown status", 0, QApplication::UnicodeUTF8)); - liftoffButton->setText(QString()); - haltButton->setText(QString()); - continueButton->setText(QString()); - landButton->setText(QString()); - shutdownButton->setText(QString()); - abortButton->setText(QString()); - killButton->setText(QString()); - } // retranslateUi - -}; - -namespace Ui -{ -class UASView: public Ui_UASView {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // UASVIEW_H diff --git a/src/ui/generated/WatchdogControl.h b/src/ui/generated/WatchdogControl.h deleted file mode 100644 index c864e860860edbf0dfff6c1a0a3dd9721132e3b5..0000000000000000000000000000000000000000 --- a/src/ui/generated/WatchdogControl.h +++ /dev/null @@ -1,68 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'WatchdogControl.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef WATCHDOGCONTROL_H -#define WATCHDOGCONTROL_H - -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_WatchdogControl -{ -public: - QVBoxLayout *verticalLayout; - QWidget *mainWidget; - QLabel *processInfoLabel; - - void setupUi(QWidget *WatchdogControl) { - if (WatchdogControl->objectName().isEmpty()) - WatchdogControl->setObjectName(QString::fromUtf8("WatchdogControl")); - WatchdogControl->resize(400, 300); - verticalLayout = new QVBoxLayout(WatchdogControl); - verticalLayout->setObjectName(QString::fromUtf8("verticalLayout")); - mainWidget = new QWidget(WatchdogControl); - mainWidget->setObjectName(QString::fromUtf8("mainWidget")); - - verticalLayout->addWidget(mainWidget); - - processInfoLabel = new QLabel(WatchdogControl); - processInfoLabel->setObjectName(QString::fromUtf8("processInfoLabel")); - - verticalLayout->addWidget(processInfoLabel); - - verticalLayout->setStretch(0, 100); - - retranslateUi(WatchdogControl); - - QMetaObject::connectSlotsByName(WatchdogControl); - } // setupUi - - void retranslateUi(QWidget *WatchdogControl) { - WatchdogControl->setWindowTitle(QApplication::translate("WatchdogControl", "Form", 0, QApplication::UnicodeUTF8)); - processInfoLabel->setText(QApplication::translate("WatchdogControl", "0 Processes Core 1: 0% Core 2: 0%", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class WatchdogControl: public Ui_WatchdogControl {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // WATCHDOGCONTROL_H diff --git a/src/ui/generated/WatchdogProcessView.h b/src/ui/generated/WatchdogProcessView.h deleted file mode 100644 index fff4589f36147700b1c889747c01a24fcde54b39..0000000000000000000000000000000000000000 --- a/src/ui/generated/WatchdogProcessView.h +++ /dev/null @@ -1,90 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'WatchdogProcessView.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef WATCHDOGPROCESSVIEW_H -#define WATCHDOGPROCESSVIEW_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_WatchdogProcessView -{ -public: - QHBoxLayout *horizontalLayout; - QLabel *nameLabel; - QLabel *pidLabel; - QLabel *argumentsLabel; - QToolButton *startButton; - QToolButton *restartButton; - - void setupUi(QWidget *WatchdogProcessView) { - if (WatchdogProcessView->objectName().isEmpty()) - WatchdogProcessView->setObjectName(QString::fromUtf8("WatchdogProcessView")); - WatchdogProcessView->resize(400, 44); - horizontalLayout = new QHBoxLayout(WatchdogProcessView); - horizontalLayout->setObjectName(QString::fromUtf8("horizontalLayout")); - nameLabel = new QLabel(WatchdogProcessView); - nameLabel->setObjectName(QString::fromUtf8("nameLabel")); - - horizontalLayout->addWidget(nameLabel); - - pidLabel = new QLabel(WatchdogProcessView); - pidLabel->setObjectName(QString::fromUtf8("pidLabel")); - - horizontalLayout->addWidget(pidLabel); - - argumentsLabel = new QLabel(WatchdogProcessView); - argumentsLabel->setObjectName(QString::fromUtf8("argumentsLabel")); - - horizontalLayout->addWidget(argumentsLabel); - - startButton = new QToolButton(WatchdogProcessView); - startButton->setObjectName(QString::fromUtf8("startButton")); - - horizontalLayout->addWidget(startButton); - - restartButton = new QToolButton(WatchdogProcessView); - restartButton->setObjectName(QString::fromUtf8("restartButton")); - - horizontalLayout->addWidget(restartButton); - - - retranslateUi(WatchdogProcessView); - - QMetaObject::connectSlotsByName(WatchdogProcessView); - } // setupUi - - void retranslateUi(QWidget *WatchdogProcessView) { - WatchdogProcessView->setWindowTitle(QApplication::translate("WatchdogProcessView", "Form", 0, QApplication::UnicodeUTF8)); - nameLabel->setText(QApplication::translate("WatchdogProcessView", "TextLabel", 0, QApplication::UnicodeUTF8)); - pidLabel->setText(QApplication::translate("WatchdogProcessView", "TextLabel", 0, QApplication::UnicodeUTF8)); - argumentsLabel->setText(QApplication::translate("WatchdogProcessView", "TextLabel", 0, QApplication::UnicodeUTF8)); - startButton->setText(QApplication::translate("WatchdogProcessView", "...", 0, QApplication::UnicodeUTF8)); - restartButton->setText(QApplication::translate("WatchdogProcessView", "...", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class WatchdogProcessView: public Ui_WatchdogProcessView {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // WATCHDOGPROCESSVIEW_H diff --git a/src/ui/generated/WatchdogView.h b/src/ui/generated/WatchdogView.h deleted file mode 100644 index 0a56712440b1aa28f7fb59900fa21f9c867ffd0b..0000000000000000000000000000000000000000 --- a/src/ui/generated/WatchdogView.h +++ /dev/null @@ -1,68 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'WatchdogView.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef WATCHDOGVIEW_H -#define WATCHDOGVIEW_H - -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_WatchdogView -{ -public: - QGridLayout *gridLayout; - QLabel *nameLabel; - QWidget *processListWidget; - - void setupUi(QWidget *WatchdogView) { - if (WatchdogView->objectName().isEmpty()) - WatchdogView->setObjectName(QString::fromUtf8("WatchdogView")); - WatchdogView->resize(400, 300); - gridLayout = new QGridLayout(WatchdogView); - gridLayout->setObjectName(QString::fromUtf8("gridLayout")); - nameLabel = new QLabel(WatchdogView); - nameLabel->setObjectName(QString::fromUtf8("nameLabel")); - - gridLayout->addWidget(nameLabel, 0, 0, 1, 1); - - processListWidget = new QWidget(WatchdogView); - processListWidget->setObjectName(QString::fromUtf8("processListWidget")); - - gridLayout->addWidget(processListWidget, 1, 0, 1, 1); - - gridLayout->setRowStretch(1, 100); - - retranslateUi(WatchdogView); - - QMetaObject::connectSlotsByName(WatchdogView); - } // setupUi - - void retranslateUi(QWidget *WatchdogView) { - WatchdogView->setWindowTitle(QApplication::translate("WatchdogView", "Form", 0, QApplication::UnicodeUTF8)); - nameLabel->setText(QApplication::translate("WatchdogView", "Watchdog", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class WatchdogView: public Ui_WatchdogView {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // WATCHDOGVIEW_H diff --git a/src/ui/generated/WaypointList.h b/src/ui/generated/WaypointList.h deleted file mode 100644 index 72df6ece185e62453407b61d36263bf444fb5293..0000000000000000000000000000000000000000 --- a/src/ui/generated/WaypointList.h +++ /dev/null @@ -1,176 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'WaypointList.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef WAYPOINTLIST_H -#define WAYPOINTLIST_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_WaypointList -{ -public: - QAction *actionAddWaypoint; - QAction *actionTransmit; - QAction *actionRead; - QGridLayout *gridLayout; - QScrollArea *scrollArea; - QWidget *scrollAreaWidgetContents; - QHBoxLayout *horizontalLayout; - QWidget *listWidget; - QPushButton *readButton; - QPushButton *transmitButton; - QLabel *statusLabel; - QToolButton *addButton; - QPushButton *loadButton; - QPushButton *saveButton; - QSpacerItem *horizontalSpacer; - QToolButton *positionAddButton; - - void setupUi(QWidget *WaypointList) { - if (WaypointList->objectName().isEmpty()) - WaypointList->setObjectName(QString::fromUtf8("WaypointList")); - WaypointList->resize(476, 218); - WaypointList->setMinimumSize(QSize(100, 120)); - actionAddWaypoint = new QAction(WaypointList); - actionAddWaypoint->setObjectName(QString::fromUtf8("actionAddWaypoint")); - QIcon icon; - icon.addFile(QString::fromUtf8(":/files/images/actions/list-add.svg"), QSize(), QIcon::Normal, QIcon::Off); - actionAddWaypoint->setIcon(icon); - actionTransmit = new QAction(WaypointList); - actionTransmit->setObjectName(QString::fromUtf8("actionTransmit")); - QIcon icon1; - icon1.addFile(QString::fromUtf8(":/files/images/devices/network-wireless.svg"), QSize(), QIcon::Normal, QIcon::Off); - actionTransmit->setIcon(icon1); - actionRead = new QAction(WaypointList); - actionRead->setObjectName(QString::fromUtf8("actionRead")); - QIcon icon2; - icon2.addFile(QString::fromUtf8(":/files/images/status/software-update-available.svg"), QSize(), QIcon::Normal, QIcon::Off); - actionRead->setIcon(icon2); - gridLayout = new QGridLayout(WaypointList); - gridLayout->setSpacing(4); - gridLayout->setContentsMargins(4, 4, 4, 4); - gridLayout->setObjectName(QString::fromUtf8("gridLayout")); - scrollArea = new QScrollArea(WaypointList); - scrollArea->setObjectName(QString::fromUtf8("scrollArea")); - scrollArea->setWidgetResizable(true); - scrollAreaWidgetContents = new QWidget(); - scrollAreaWidgetContents->setObjectName(QString::fromUtf8("scrollAreaWidgetContents")); - scrollAreaWidgetContents->setGeometry(QRect(0, 0, 466, 149)); - horizontalLayout = new QHBoxLayout(scrollAreaWidgetContents); - horizontalLayout->setSpacing(0); - horizontalLayout->setContentsMargins(4, 4, 4, 4); - horizontalLayout->setObjectName(QString::fromUtf8("horizontalLayout")); - listWidget = new QWidget(scrollAreaWidgetContents); - listWidget->setObjectName(QString::fromUtf8("listWidget")); - - horizontalLayout->addWidget(listWidget); - - scrollArea->setWidget(scrollAreaWidgetContents); - - gridLayout->addWidget(scrollArea, 0, 0, 1, 9); - - readButton = new QPushButton(WaypointList); - readButton->setObjectName(QString::fromUtf8("readButton")); - readButton->setIcon(icon2); - - gridLayout->addWidget(readButton, 2, 7, 1, 1); - - transmitButton = new QPushButton(WaypointList); - transmitButton->setObjectName(QString::fromUtf8("transmitButton")); - transmitButton->setIcon(icon1); - - gridLayout->addWidget(transmitButton, 2, 8, 1, 1); - - statusLabel = new QLabel(WaypointList); - statusLabel->setObjectName(QString::fromUtf8("statusLabel")); - - gridLayout->addWidget(statusLabel, 3, 0, 1, 9); - - addButton = new QToolButton(WaypointList); - addButton->setObjectName(QString::fromUtf8("addButton")); - addButton->setIcon(icon); - - gridLayout->addWidget(addButton, 2, 6, 1, 1); - - loadButton = new QPushButton(WaypointList); - loadButton->setObjectName(QString::fromUtf8("loadButton")); - - gridLayout->addWidget(loadButton, 2, 3, 1, 1); - - saveButton = new QPushButton(WaypointList); - saveButton->setObjectName(QString::fromUtf8("saveButton")); - - gridLayout->addWidget(saveButton, 2, 2, 1, 1); - - horizontalSpacer = new QSpacerItem(127, 20, QSizePolicy::Expanding, QSizePolicy::Minimum); - - gridLayout->addItem(horizontalSpacer, 2, 4, 1, 1); - - positionAddButton = new QToolButton(WaypointList); - positionAddButton->setObjectName(QString::fromUtf8("positionAddButton")); - QIcon icon3; - icon3.addFile(QString::fromUtf8(":/files/images/actions/go-bottom.svg"), QSize(), QIcon::Normal, QIcon::Off); - positionAddButton->setIcon(icon3); - - gridLayout->addWidget(positionAddButton, 2, 5, 1, 1); - - gridLayout->setRowStretch(0, 100); - - retranslateUi(WaypointList); - - QMetaObject::connectSlotsByName(WaypointList); - } // setupUi - - void retranslateUi(QWidget *WaypointList) { - WaypointList->setWindowTitle(QApplication::translate("WaypointList", "Form", 0, QApplication::UnicodeUTF8)); - actionAddWaypoint->setText(QApplication::translate("WaypointList", "Add Waypoint", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - actionAddWaypoint->setToolTip(QApplication::translate("WaypointList", "Add a new waypoint to the end of the list", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - actionTransmit->setText(QApplication::translate("WaypointList", "Transmit", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - actionTransmit->setToolTip(QApplication::translate("WaypointList", "Transmit waypoints to unmanned system", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - actionRead->setText(QApplication::translate("WaypointList", "Read", 0, QApplication::UnicodeUTF8)); - readButton->setText(QApplication::translate("WaypointList", "Read", 0, QApplication::UnicodeUTF8)); - transmitButton->setText(QApplication::translate("WaypointList", "Write", 0, QApplication::UnicodeUTF8)); - statusLabel->setText(QApplication::translate("WaypointList", "TextLabel", 0, QApplication::UnicodeUTF8)); - addButton->setText(QApplication::translate("WaypointList", "...", 0, QApplication::UnicodeUTF8)); - loadButton->setText(QApplication::translate("WaypointList", "Load WPs", 0, QApplication::UnicodeUTF8)); - saveButton->setText(QApplication::translate("WaypointList", "Save WPs", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - positionAddButton->setToolTip(QApplication::translate("WaypointList", "Set the current vehicle position as new waypoint", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - positionAddButton->setText(QApplication::translate("WaypointList", "...", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class WaypointList: public Ui_WaypointList {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // WAYPOINTLIST_H diff --git a/src/ui/generated/WaypointView.h b/src/ui/generated/WaypointView.h deleted file mode 100644 index b4cffa42589a2a14564832feeedc40c36a421c28..0000000000000000000000000000000000000000 --- a/src/ui/generated/WaypointView.h +++ /dev/null @@ -1,359 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'WaypointView.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef WAYPOINTVIEW_H -#define WAYPOINTVIEW_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_WaypointView -{ -public: - QGridLayout *gridLayout; - QGroupBox *groupBox; - QHBoxLayout *horizontalLayout; - QCheckBox *selectedBox; - QLabel *idLabel; - QSpacerItem *horizontalSpacer_2; - QDoubleSpinBox *xSpinBox; - QDoubleSpinBox *ySpinBox; - QDoubleSpinBox *zSpinBox; - QSpinBox *yawSpinBox; - QDoubleSpinBox *orbitSpinBox; - QSpinBox *holdTimeSpinBox; - QCheckBox *autoContinue; - QPushButton *upButton; - QPushButton *downButton; - QPushButton *removeButton; - - void setupUi(QWidget *WaypointView) { - if (WaypointView->objectName().isEmpty()) - WaypointView->setObjectName(QString::fromUtf8("WaypointView")); - WaypointView->resize(763, 40); - QSizePolicy sizePolicy(QSizePolicy::Maximum, QSizePolicy::Fixed); - sizePolicy.setHorizontalStretch(0); - sizePolicy.setVerticalStretch(0); - sizePolicy.setHeightForWidth(WaypointView->sizePolicy().hasHeightForWidth()); - WaypointView->setSizePolicy(sizePolicy); - WaypointView->setMinimumSize(QSize(200, 0)); - gridLayout = new QGridLayout(WaypointView); - gridLayout->setSpacing(0); - gridLayout->setContentsMargins(0, 0, 0, 0); - gridLayout->setObjectName(QString::fromUtf8("gridLayout")); - groupBox = new QGroupBox(WaypointView); - groupBox->setObjectName(QString::fromUtf8("groupBox")); - horizontalLayout = new QHBoxLayout(groupBox); - horizontalLayout->setSpacing(2); - horizontalLayout->setContentsMargins(5, 5, 5, 5); - horizontalLayout->setObjectName(QString::fromUtf8("horizontalLayout")); - selectedBox = new QCheckBox(groupBox); - selectedBox->setObjectName(QString::fromUtf8("selectedBox")); - selectedBox->setIconSize(QSize(16, 16)); - - horizontalLayout->addWidget(selectedBox); - - idLabel = new QLabel(groupBox); - idLabel->setObjectName(QString::fromUtf8("idLabel")); - idLabel->setMinimumSize(QSize(15, 0)); - idLabel->setAlignment(Qt::AlignCenter); - - horizontalLayout->addWidget(idLabel); - - horizontalSpacer_2 = new QSpacerItem(25, 12, QSizePolicy::Expanding, QSizePolicy::Minimum); - - horizontalLayout->addItem(horizontalSpacer_2); - - xSpinBox = new QDoubleSpinBox(groupBox); - xSpinBox->setObjectName(QString::fromUtf8("xSpinBox")); - xSpinBox->setMinimum(-1000); - xSpinBox->setMaximum(1000); - xSpinBox->setSingleStep(0.05); - - horizontalLayout->addWidget(xSpinBox); - - ySpinBox = new QDoubleSpinBox(groupBox); - ySpinBox->setObjectName(QString::fromUtf8("ySpinBox")); - ySpinBox->setMinimum(-1000); - ySpinBox->setMaximum(1000); - ySpinBox->setSingleStep(0.05); - ySpinBox->setValue(0); - - horizontalLayout->addWidget(ySpinBox); - - zSpinBox = new QDoubleSpinBox(groupBox); - zSpinBox->setObjectName(QString::fromUtf8("zSpinBox")); - zSpinBox->setMinimum(-1000); - zSpinBox->setMaximum(0); - zSpinBox->setSingleStep(0.05); - - horizontalLayout->addWidget(zSpinBox); - - yawSpinBox = new QSpinBox(groupBox); - yawSpinBox->setObjectName(QString::fromUtf8("yawSpinBox")); - yawSpinBox->setWrapping(true); - yawSpinBox->setMinimum(-180); - yawSpinBox->setMaximum(180); - yawSpinBox->setSingleStep(10); - - horizontalLayout->addWidget(yawSpinBox); - - orbitSpinBox = new QDoubleSpinBox(groupBox); - orbitSpinBox->setObjectName(QString::fromUtf8("orbitSpinBox")); - orbitSpinBox->setMinimum(0.05); - orbitSpinBox->setMaximum(1); - orbitSpinBox->setSingleStep(0.05); - - horizontalLayout->addWidget(orbitSpinBox); - - holdTimeSpinBox = new QSpinBox(groupBox); - holdTimeSpinBox->setObjectName(QString::fromUtf8("holdTimeSpinBox")); - holdTimeSpinBox->setMaximum(60000); - holdTimeSpinBox->setSingleStep(500); - holdTimeSpinBox->setValue(0); - - horizontalLayout->addWidget(holdTimeSpinBox); - - autoContinue = new QCheckBox(groupBox); - autoContinue->setObjectName(QString::fromUtf8("autoContinue")); - - horizontalLayout->addWidget(autoContinue); - - upButton = new QPushButton(groupBox); - upButton->setObjectName(QString::fromUtf8("upButton")); - upButton->setMinimumSize(QSize(28, 22)); - QIcon icon; - icon.addFile(QString::fromUtf8(":/files/images/actions/go-up.svg"), QSize(), QIcon::Normal, QIcon::Off); - upButton->setIcon(icon); - - horizontalLayout->addWidget(upButton); - - downButton = new QPushButton(groupBox); - downButton->setObjectName(QString::fromUtf8("downButton")); - downButton->setMinimumSize(QSize(28, 22)); - QIcon icon1; - icon1.addFile(QString::fromUtf8(":/files/images/actions/go-down.svg"), QSize(), QIcon::Normal, QIcon::Off); - downButton->setIcon(icon1); - - horizontalLayout->addWidget(downButton); - - removeButton = new QPushButton(groupBox); - removeButton->setObjectName(QString::fromUtf8("removeButton")); - removeButton->setMinimumSize(QSize(28, 22)); - QIcon icon2; - icon2.addFile(QString::fromUtf8(":/files/images/actions/list-remove.svg"), QSize(), QIcon::Normal, QIcon::Off); - removeButton->setIcon(icon2); - - horizontalLayout->addWidget(removeButton); - - - gridLayout->addWidget(groupBox, 0, 0, 1, 1); - - - retranslateUi(WaypointView); - - QMetaObject::connectSlotsByName(WaypointView); - } // setupUi - - void retranslateUi(QWidget *WaypointView) { - WaypointView->setWindowTitle(QApplication::translate("WaypointView", "Form", 0, QApplication::UnicodeUTF8)); - WaypointView->setStyleSheet(QApplication::translate("WaypointView", "QWidget#colorIcon {}\n" - "\n" - "QWidget {\n" - "background-color: #252528;\n" - "color: #DDDDDF;\n" - "border-color: #EEEEEE;\n" - "background-clip: border;\n" - "}\n" - "\n" - "QCheckBox {\n" - "background-color: #252528;\n" - "color: #454545;\n" - "}\n" - "\n" - "QGroupBox {\n" - " border: 1px solid #EEEEEE;\n" - " border-radius: 5px;\n" - " padding: 0px 0px 0px 0px;\n" - "margin-top: 1ex; /* leave space at the top for the title */\n" - " margin: 0px;\n" - "}\n" - "\n" - " QGroupBox::title {\n" - " subcontrol-origin: margin;\n" - " subcontrol-position: top center; /* position at the top center */\n" - " margin: 0 3px 0px 3px;\n" - " padding: 0 3px 0px 0px;\n" - " font: bold 8px;\n" - " }\n" - "\n" - "QGroupBox#heartbeatIcon {\n" - " background-color: red;\n" - "}\n" - "\n" - " QDockWidget {\n" - " font: bold;\n" - " border: 1px solid #32345E;\n" - "}\n" - "\n" - "QPushButton {\n" - " font-weight: bold;\n" - " font-size: 12px;\n" - " border: 1px solid #999999;\n" - " border-radius: 10px;\n" - " min-width:22px;\n" - " max-width: 36px;\n" - " min-height: 16px;\n" - " max-height:" - " 16px;\n" - " padding: 2px;\n" - " background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #777777, stop: 1 #555555);\n" - "}\n" - "\n" - "QPushButton:pressed {\n" - " background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #444444, stop: 1 #555555);\n" - "}\n" - "\n" - "QPushButton#landButton {\n" - " color: #000000;\n" - " background: qlineargradient(x1:0, y1:0, x2:0, y2:1,\n" - " stop:0 #ffee01, stop:1 #ae8f00) url(\"ICONDIR/control/emergency-button.png\");\n" - "}\n" - "\n" - "QPushButton:pressed#landButton {\n" - " color: #000000;\n" - " background: qlineargradient(x1:0, y1:0, x2:0, y2:1,\n" - " stop:0 #bbaa00, stop:1 #a05b00) url(\"ICONDIR/control/emergency-button.png\");\n" - "}\n" - "\n" - "QPushButton#killButton {\n" - " color: #000000;\n" - " background: qlineargradient(x1:0, y1:0, x2:0, y2:1,\n" - " stop:0 #ffb917, stop:1 #b37300) url(\"ICONDIR/control/emergency-button.png\");\n" - "}\n" - "\n" - "QPushButton:pressed#killButton {\n" - " color: " - "#000000;\n" - " background: qlineargradient(x1:0, y1:0, x2:0, y2:1,\n" - " stop:0 #bb8500, stop:1 #903000) url(\"ICONDIR/control/emergency-button.png\");\n" - "}\n" - "\n" - "QProgressBar {\n" - " border: 1px solid white;\n" - " border-radius: 4px;\n" - " text-align: center;\n" - " padding: 2px;\n" - " color: white;\n" - " background-color: #111111;\n" - "}\n" - "\n" - "QProgressBar:horizontal {\n" - " height: 12px;\n" - "}\n" - "\n" - "QProgressBar QLabel {\n" - " font-size: 8px;\n" - "}\n" - "\n" - "QProgressBar:vertical {\n" - " width: 12px;\n" - "}\n" - "\n" - "QProgressBar::chunk {\n" - " background-color: #656565;\n" - "}\n" - "\n" - "QProgressBar::chunk#batteryBar {\n" - " background-color: green;\n" - "}\n" - "\n" - "QProgressBar::chunk#speedBar {\n" - " background-color: yellow;\n" - "}\n" - "\n" - "QProgressBar::chunk#thrustBar {\n" - " background-color: orange;\n" - "}", 0, QApplication::UnicodeUTF8)); - groupBox->setTitle(QString()); -#ifndef QT_NO_TOOLTIP - selectedBox->setToolTip(QApplication::translate("WaypointView", "Currently selected waypoint", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - selectedBox->setText(QString()); -#ifndef QT_NO_TOOLTIP - idLabel->setToolTip(QApplication::translate("WaypointView", "Waypoint Sequence Number", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - idLabel->setText(QApplication::translate("WaypointView", "TextLabel", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - xSpinBox->setToolTip(QApplication::translate("WaypointView", "Position X coordinate", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - xSpinBox->setSuffix(QApplication::translate("WaypointView", " m", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - ySpinBox->setToolTip(QApplication::translate("WaypointView", "Position Y coordinate", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - ySpinBox->setSuffix(QApplication::translate("WaypointView", " m", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - zSpinBox->setToolTip(QApplication::translate("WaypointView", "Position Z coordinate", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - zSpinBox->setSuffix(QApplication::translate("WaypointView", " m", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - yawSpinBox->setToolTip(QApplication::translate("WaypointView", "Yaw angle", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - yawSpinBox->setSuffix(QApplication::translate("WaypointView", "\302\260", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - orbitSpinBox->setToolTip(QApplication::translate("WaypointView", "Orbit radius", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - orbitSpinBox->setSuffix(QApplication::translate("WaypointView", " m", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_STATUSTIP - holdTimeSpinBox->setStatusTip(QApplication::translate("WaypointView", "Time in milliseconds that the MAV has to stay inside the orbit before advancing", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_STATUSTIP - holdTimeSpinBox->setSuffix(QApplication::translate("WaypointView", " ms", 0, QApplication::UnicodeUTF8)); -#ifndef QT_NO_TOOLTIP - autoContinue->setToolTip(QApplication::translate("WaypointView", "Automatically continue after this waypoint", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - autoContinue->setText(QString()); -#ifndef QT_NO_TOOLTIP - upButton->setToolTip(QApplication::translate("WaypointView", "Move Up", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - upButton->setText(QString()); -#ifndef QT_NO_TOOLTIP - downButton->setToolTip(QApplication::translate("WaypointView", "Move Down", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - downButton->setText(QString()); -#ifndef QT_NO_TOOLTIP - removeButton->setToolTip(QApplication::translate("WaypointView", "Delete", 0, QApplication::UnicodeUTF8)); -#endif // QT_NO_TOOLTIP - removeButton->setText(QString()); - } // retranslateUi - -}; - -namespace Ui -{ -class WaypointView: public Ui_WaypointView {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // WAYPOINTVIEW_H diff --git a/src/ui/generated/XMLCommProtocolWidget.h b/src/ui/generated/XMLCommProtocolWidget.h deleted file mode 100644 index 274f8177bd4ab88f8ecb573c492deee5cf2211b4..0000000000000000000000000000000000000000 --- a/src/ui/generated/XMLCommProtocolWidget.h +++ /dev/null @@ -1,152 +0,0 @@ -/******************************************************************************** -** Form generated from reading UI file 'XMLCommProtocolWidget.ui' -** -** Created: Sun Jul 11 18:53:34 2010 -** by: Qt User Interface Compiler version 4.6.2 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef XMLCOMMPROTOCOLWIDGET_H -#define XMLCOMMPROTOCOLWIDGET_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_XMLCommProtocolWidget -{ -public: - QGridLayout *gridLayout; - QLabel *fileNameLabel; - QPushButton *selectFileButton; - QTextEdit *xmlTextView; - QLabel *outputDirNameLabel; - QPushButton *selectOutputButton; - QTreeView *xmlTreeView; - QLabel *label; - QPlainTextEdit *compileLog; - QLabel *validXMLLabel; - QPushButton *saveButton; - QPushButton *generateButton; - - void setupUi(QWidget *XMLCommProtocolWidget) { - if (XMLCommProtocolWidget->objectName().isEmpty()) - XMLCommProtocolWidget->setObjectName(QString::fromUtf8("XMLCommProtocolWidget")); - XMLCommProtocolWidget->resize(846, 480); - gridLayout = new QGridLayout(XMLCommProtocolWidget); - gridLayout->setSpacing(12); - gridLayout->setObjectName(QString::fromUtf8("gridLayout")); - gridLayout->setContentsMargins(-1, 6, 6, 6); - fileNameLabel = new QLabel(XMLCommProtocolWidget); - fileNameLabel->setObjectName(QString::fromUtf8("fileNameLabel")); - fileNameLabel->setMaximumSize(QSize(300, 16777215)); - fileNameLabel->setScaledContents(true); - fileNameLabel->setAlignment(Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter); - - gridLayout->addWidget(fileNameLabel, 0, 0, 1, 1); - - selectFileButton = new QPushButton(XMLCommProtocolWidget); - selectFileButton->setObjectName(QString::fromUtf8("selectFileButton")); - QIcon icon; - icon.addFile(QString::fromUtf8(":/files/images/status/folder-open.svg"), QSize(), QIcon::Normal, QIcon::Off); - selectFileButton->setIcon(icon); - - gridLayout->addWidget(selectFileButton, 0, 2, 1, 1); - - xmlTextView = new QTextEdit(XMLCommProtocolWidget); - xmlTextView->setObjectName(QString::fromUtf8("xmlTextView")); - xmlTextView->setReadOnly(false); - - gridLayout->addWidget(xmlTextView, 0, 3, 6, 1); - - outputDirNameLabel = new QLabel(XMLCommProtocolWidget); - outputDirNameLabel->setObjectName(QString::fromUtf8("outputDirNameLabel")); - outputDirNameLabel->setMaximumSize(QSize(400, 16777215)); - outputDirNameLabel->setScaledContents(true); - - gridLayout->addWidget(outputDirNameLabel, 1, 0, 1, 2); - - selectOutputButton = new QPushButton(XMLCommProtocolWidget); - selectOutputButton->setObjectName(QString::fromUtf8("selectOutputButton")); - selectOutputButton->setIcon(icon); - - gridLayout->addWidget(selectOutputButton, 1, 2, 1, 1); - - xmlTreeView = new QTreeView(XMLCommProtocolWidget); - xmlTreeView->setObjectName(QString::fromUtf8("xmlTreeView")); - - gridLayout->addWidget(xmlTreeView, 2, 0, 1, 3); - - label = new QLabel(XMLCommProtocolWidget); - label->setObjectName(QString::fromUtf8("label")); - - gridLayout->addWidget(label, 3, 0, 1, 2); - - compileLog = new QPlainTextEdit(XMLCommProtocolWidget); - compileLog->setObjectName(QString::fromUtf8("compileLog")); - - gridLayout->addWidget(compileLog, 4, 0, 1, 3); - - validXMLLabel = new QLabel(XMLCommProtocolWidget); - validXMLLabel->setObjectName(QString::fromUtf8("validXMLLabel")); - - gridLayout->addWidget(validXMLLabel, 5, 0, 1, 1); - - saveButton = new QPushButton(XMLCommProtocolWidget); - saveButton->setObjectName(QString::fromUtf8("saveButton")); - - gridLayout->addWidget(saveButton, 5, 1, 1, 1); - - generateButton = new QPushButton(XMLCommProtocolWidget); - generateButton->setObjectName(QString::fromUtf8("generateButton")); - QIcon icon1; - icon1.addFile(QString::fromUtf8(":/files/images/categories/applications-system.svg"), QSize(), QIcon::Normal, QIcon::Off); - generateButton->setIcon(icon1); - - gridLayout->addWidget(generateButton, 5, 2, 1, 1); - - gridLayout->setRowStretch(2, 100); - gridLayout->setColumnStretch(0, 1); - gridLayout->setColumnStretch(1, 1); - gridLayout->setColumnStretch(2, 1); - gridLayout->setColumnStretch(3, 100); - - retranslateUi(XMLCommProtocolWidget); - - QMetaObject::connectSlotsByName(XMLCommProtocolWidget); - } // setupUi - - void retranslateUi(QWidget *XMLCommProtocolWidget) { - XMLCommProtocolWidget->setWindowTitle(QApplication::translate("XMLCommProtocolWidget", "Form", 0, QApplication::UnicodeUTF8)); - fileNameLabel->setText(QApplication::translate("XMLCommProtocolWidget", "Select input file", 0, QApplication::UnicodeUTF8)); - selectFileButton->setText(QApplication::translate("XMLCommProtocolWidget", "Select input file", 0, QApplication::UnicodeUTF8)); - outputDirNameLabel->setText(QApplication::translate("XMLCommProtocolWidget", "Select output directory", 0, QApplication::UnicodeUTF8)); - selectOutputButton->setText(QApplication::translate("XMLCommProtocolWidget", "Select directory", 0, QApplication::UnicodeUTF8)); - label->setText(QApplication::translate("XMLCommProtocolWidget", "Compile Output", 0, QApplication::UnicodeUTF8)); - validXMLLabel->setText(QApplication::translate("XMLCommProtocolWidget", "No file loaded", 0, QApplication::UnicodeUTF8)); - saveButton->setText(QApplication::translate("XMLCommProtocolWidget", "Save file", 0, QApplication::UnicodeUTF8)); - generateButton->setText(QApplication::translate("XMLCommProtocolWidget", "Save and generate", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui -{ -class XMLCommProtocolWidget: public Ui_XMLCommProtocolWidget {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // XMLCOMMPROTOCOLWIDGET_H diff --git a/src/ui/map3D/Pixhawk3DWidget.cc b/src/ui/map3D/Pixhawk3DWidget.cc index 474b445be1e5440c2ae70e7048474664fc57e37b..c91367d54f038297982c97362676a179e03fb75d 100644 --- a/src/ui/map3D/Pixhawk3DWidget.cc +++ b/src/ui/map3D/Pixhawk3DWidget.cc @@ -48,11 +48,6 @@ #include "QGC.h" #include "gpl.h" -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) -#include -#include -#endif - Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent) : kMessageTimeout(4.0) , mMode(DEFAULT_MODE) @@ -148,10 +143,6 @@ Pixhawk3DWidget::systemCreated(UASInterface *uas) this, SLOT(setpointChanged(int,float,float,float,float))); connect(uas, SIGNAL(homePositionChanged(int,double,double,double)), this, SLOT(homePositionChanged(int,double,double,double))); -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - connect(uas, SIGNAL(overlayChanged(UASInterface*)), - this, SLOT(addOverlay(UASInterface*))); -#endif // mSystemContainerMap[systemId].gpsLocalOrigin() = QVector3D(47.397786, 8.544476, 428); initializeSystem(systemId, uas->getColor()); @@ -633,43 +624,6 @@ Pixhawk3DWidget::loadTerrainModel(void) } } -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) -void -Pixhawk3DWidget::addOverlay(UASInterface *uas) -{ - int systemId = uas->getUASID(); - - if (!mSystemContainerMap.contains(systemId)) - { - return; - } - - SystemContainer& systemData = mSystemContainerMap[systemId]; - - qreal receivedTimestamp; - px::GLOverlay overlay = uas->getOverlay(receivedTimestamp); - - QString overlayName = QString::fromStdString(overlay.name()); - - osg::ref_ptr& systemNode = m3DWidget->systemGroup(systemId); - - if (!systemData.overlayNodeMap().contains(overlayName)) - { - osg::ref_ptr overlayNode = new GLOverlayGeode; - systemData.overlayNodeMap().insert(overlayName, overlayNode); - - systemNode->allocentricMap()->addChild(overlayNode, false); - systemNode->rollingMap()->addChild(overlayNode, false); - - emit overlayCreatedSignal(systemId, overlayName); - } - - osg::ref_ptr& overlayNode = systemData.overlayNodeMap()[overlayName]; - overlayNode->setOverlay(overlay); - overlayNode->setMessageTimestamp(receivedTimestamp); -} -#endif - void Pixhawk3DWidget::selectTargetHeading(void) { @@ -1123,42 +1077,6 @@ Pixhawk3DWidget::updateWidget(void) systemViewParams->displayTrails()); rollingMap->setChildValue(systemData.waypointGroupNode(), systemViewParams->displayWaypoints()); - -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - rollingMap->setChildValue(systemData.obstacleGroupNode(), - systemViewParams->displayObstacleList()); - - QMutableMapIterator > itOverlay(systemData.overlayNodeMap()); - while (itOverlay.hasNext()) - { - itOverlay.next(); - - osg::ref_ptr& overlayNode = itOverlay.value(); - - bool displayOverlay = systemViewParams->displayOverlay().value(itOverlay.key()); - - bool visible; - visible = (overlayNode->coordinateFrameType() == px::GLOverlay::GLOBAL) && - displayOverlay && - (QGC::groundTimeSeconds() - overlayNode->messageTimestamp() < kMessageTimeout); - - allocentricMap->setChildValue(overlayNode, visible); - - visible = (overlayNode->coordinateFrameType() == px::GLOverlay::LOCAL) && - displayOverlay && - (QGC::groundTimeSeconds() - overlayNode->messageTimestamp() < kMessageTimeout);; - - rollingMap->setChildValue(overlayNode, visible); - } - - rollingMap->setChildValue(systemData.plannedPathNode(), - systemViewParams->displayPlannedPath()); - - m3DWidget->hudGroup()->setChildValue(systemData.depthImageNode(), - systemViewParams->displayRGBD()); - m3DWidget->hudGroup()->setChildValue(systemData.rgbImageNode(), - systemViewParams->displayRGBD()); -#endif } if (mFollowCameraId != -1) @@ -1248,41 +1166,6 @@ Pixhawk3DWidget::updateWidget(void) { updateWaypoints(uas, frame, systemData.waypointGroupNode()); } - -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - if (systemViewParams->displayObstacleList()) - { - updateObstacles(uas, frame, x, y, z, systemData.obstacleGroupNode()); - } - if (systemViewParams->displayPlannedPath()) - { - updatePlannedPath(uas, frame, x, y, z, systemData.plannedPathNode()); - } - if (systemViewParams->displayPointCloud()) - { - updatePointCloud(uas, frame, x, y, z, systemData.pointCloudNode(), - systemViewParams->colorPointCloudByDistance()); - } - if (systemViewParams->displayRGBD()) - { - updateRGBD(uas, frame, systemData.rgbImageNode(), - systemData.depthImageNode()); - } - - if (frame == MAV_FRAME_LOCAL_NED && - mGlobalViewParams->imageryType() != Imagery::BLANK_MAP && - !systemData.gpsLocalOrigin().isNull() && - mActiveUAS->getUASID() == systemId) - { - const QVector3D& gpsLocalOrigin = systemData.gpsLocalOrigin(); - - double utmX, utmY; - QString utmZone; - Imagery::LLtoUTM(gpsLocalOrigin.x(), gpsLocalOrigin.y(), utmX, utmY, utmZone); - - updateImagery(utmX, utmY, utmZone, frame); - } -#endif } if (frame == MAV_FRAME_GLOBAL && @@ -1648,17 +1531,6 @@ Pixhawk3DWidget::initializeSystem(int systemId, const QColor& systemColor) systemData.waypointGroupNode()->init(); systemNode->rollingMap()->addChild(systemData.waypointGroupNode(), false); -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - systemData.obstacleGroupNode() = new ObstacleGroupNode; - systemData.obstacleGroupNode()->init(); - systemNode->rollingMap()->addChild(systemData.obstacleGroupNode(), false); - - // generate path model - systemData.plannedPathNode() = new osg::Geode; - systemData.plannedPathNode()->addDrawable(createTrail(osg::Vec4(1.0f, 0.8f, 0.0f, 1.0f))); - systemNode->rollingMap()->addChild(systemData.plannedPathNode(), false); -#endif - systemData.rgbImageNode() = new ImageWindowGeode; systemData.rgbImageNode()->init("RGB Image", osg::Vec4(0.0f, 0.0f, 0.1f, 1.0f), m3DWidget->font()); @@ -2390,229 +2262,6 @@ Pixhawk3DWidget::updateWaypoints(UASInterface* uas, MAV_FRAME frame, waypointGroupNode->update(uas, frame); } -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - -void -Pixhawk3DWidget::updateObstacles(UASInterface* uas, MAV_FRAME frame, - double robotX, double robotY, double robotZ, - osg::ref_ptr& obstacleGroupNode) -{ - if (frame == MAV_FRAME_GLOBAL) - { - obstacleGroupNode->clear(); - return; - } - - qreal receivedTimestamp; - px::ObstacleList obstacleList = uas->getObstacleList(receivedTimestamp); - - if (QGC::groundTimeSeconds() - receivedTimestamp < kMessageTimeout) - { - obstacleGroupNode->update(robotX, robotY, robotZ, obstacleList); - } - else - { - obstacleGroupNode->clear(); - } -} - -void -Pixhawk3DWidget::updatePlannedPath(UASInterface* uas, MAV_FRAME frame, - double robotX, double robotY, double robotZ, - osg::ref_ptr& plannedPathNode) -{ - Q_UNUSED(frame); - - qreal receivedTimestamp; - px::Path path = uas->getPath(receivedTimestamp); - - osg::Geometry* geometry = plannedPathNode->getDrawable(0)->asGeometry(); - osg::DrawArrays* drawArrays = reinterpret_cast(geometry->getPrimitiveSet(0)); - osg::Vec4Array* colorArray = reinterpret_cast(geometry->getColorArray()); - - geometry->setColorBinding(osg::Geometry::BIND_PER_VERTEX); - osg::ref_ptr linewidth(new osg::LineWidth()); - linewidth->setWidth(2.0f); - geometry->getStateSet()->setAttributeAndModes(linewidth, osg::StateAttribute::ON); - - colorArray->clear(); - - osg::ref_ptr vertices(new osg::Vec3Array); - - if (QGC::groundTimeSeconds() - receivedTimestamp < kMessageTimeout) - { - // find path length - float length = 0.0f; - for (int i = 0; i < path.waypoints_size() - 1; ++i) - { - const px::Waypoint& wp0 = path.waypoints(i); - const px::Waypoint& wp1 = path.waypoints(i+1); - - length += qgc::hypot3f(wp0.x() - wp1.x(), - wp0.y() - wp1.y(), - wp0.z() - wp1.z()); - } - - // build path - if (path.waypoints_size() > 0) - { - const px::Waypoint& wp0 = path.waypoints(0); - - vertices->push_back(osg::Vec3d(wp0.y() - robotY, - wp0.x() - robotX, - -(wp0.z() - robotZ))); - - float r, g, b; - qgc::colormap("autumn", 0, r, g, b); - colorArray->push_back(osg::Vec4d(r, g, b, 1.0f)); - } - - float lengthCurrent = 0.0f; - for (int i = 0; i < path.waypoints_size() - 1; ++i) - { - const px::Waypoint& wp0 = path.waypoints(i); - const px::Waypoint& wp1 = path.waypoints(i+1); - - lengthCurrent += qgc::hypot3f(wp0.x() - wp1.x(), - wp0.y() - wp1.y(), - wp0.z() - wp1.z()); - - vertices->push_back(osg::Vec3d(wp1.y() - robotY, - wp1.x() - robotX, - -(wp1.z() - robotZ))); - - int colorIdx = lengthCurrent / length * 127.0f; - - float r, g, b; - qgc::colormap("autumn", colorIdx, r, g, b); - colorArray->push_back(osg::Vec4f(r, g, b, 1.0f)); - } - } - - geometry->setVertexArray(vertices); - drawArrays->setFirst(0); - drawArrays->setCount(vertices->size()); - geometry->dirtyBound(); -} - -void -Pixhawk3DWidget::updateRGBD(UASInterface* uas, MAV_FRAME frame, - osg::ref_ptr& rgbImageNode, - osg::ref_ptr& depthImageNode) -{ - Q_UNUSED(frame); - - qreal receivedTimestamp; - px::RGBDImage rgbdImage = uas->getRGBDImage(receivedTimestamp); - - if (rgbdImage.rows() > 0 && rgbdImage.cols() > 0 && - QGC::groundTimeSeconds() - receivedTimestamp < kMessageTimeout) - { - rgbImageNode->image()->setImage(rgbdImage.cols(), rgbdImage.rows(), 1, - GL_LUMINANCE, GL_LUMINANCE, GL_UNSIGNED_BYTE, - reinterpret_cast(&(*(rgbdImage.mutable_imagedata1()))[0]), - osg::Image::NO_DELETE); - rgbImageNode->image()->dirty(); - - QByteArray coloredDepth(rgbdImage.cols() * rgbdImage.rows() * 3, 0); - for (uint32_t r = 0; r < rgbdImage.rows(); ++r) - { - const float* depth = reinterpret_cast(rgbdImage.imagedata2().c_str() + r * rgbdImage.step2()); - uint8_t* pixel = reinterpret_cast(coloredDepth.data()) + r * rgbdImage.cols() * 3; - for (uint32_t c = 0; c < rgbdImage.cols(); ++c) - { - if (depth[c] != 0) - { - int idx = fminf(depth[c], 7.0f) / 7.0f * 127.0f; - idx = 127 - idx; - - float r, g, b; - qgc::colormap("jet", idx, r, g, b); - pixel[0] = r * 255.0f; - pixel[1] = g * 255.0f; - pixel[2] = b * 255.0f; - } - - pixel += 3; - } - } - - depthImageNode->image()->setImage(rgbdImage.cols(), rgbdImage.rows(), 1, - GL_RGB, GL_RGB, GL_UNSIGNED_BYTE, - reinterpret_cast(coloredDepth.data()), - osg::Image::NO_DELETE); - depthImageNode->image()->dirty(); - } -} - -void -Pixhawk3DWidget::updatePointCloud(UASInterface* uas, MAV_FRAME frame, - double robotX, double robotY, double robotZ, - osg::ref_ptr& pointCloudNode, - bool colorPointCloudByDistance) -{ - Q_UNUSED(frame); - - qreal receivedTimestamp; - px::PointCloudXYZRGB pointCloud = uas->getPointCloud(receivedTimestamp); - - osg::Geometry* geometry = pointCloudNode->getDrawable(0)->asGeometry(); - osg::Vec3Array* vertices = static_cast(geometry->getVertexArray()); - osg::Vec4Array* colors = static_cast(geometry->getColorArray()); - - if (QGC::groundTimeSeconds() - receivedTimestamp > kMessageTimeout) - { - geometry->removePrimitiveSet(0, geometry->getNumPrimitiveSets()); - return; - } - - for (int i = 0; i < pointCloud.points_size(); ++i) - { - const px::PointCloudXYZRGB_PointXYZRGB& p = pointCloud.points(i); - - double x = p.x() - robotX; - double y = p.y() - robotY; - double z = p.z() - robotZ; - - - (*vertices)[i].set(y, x, -z); - - if (!colorPointCloudByDistance) - { - float rgb = p.rgb(); - - float b = *(reinterpret_cast(&rgb)) / 255.0f; - float g = *(1 + reinterpret_cast(&rgb)) / 255.0f; - float r = *(2 + reinterpret_cast(&rgb)) / 255.0f; - - (*colors)[i].set(r, g, b, 1.0f); - } - else - { - double dist = sqrt(x * x + y * y + z * z); - int colorIndex = static_cast(fmin(dist / 7.0 * 127.0, 127.0)); - - float r, g, b; - qgc::colormap("jet", colorIndex, r, g, b); - - (*colors)[i].set(r, g, b, 1.0f); - } - } - - if (geometry->getNumPrimitiveSets() == 0) - { - geometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::POINTS, - 0, pointCloud.points_size())); - } - else - { - osg::DrawArrays* drawarrays = static_cast(geometry->getPrimitiveSet(0)); - drawarrays->setCount(pointCloud.points_size()); - } -} - -#endif - int Pixhawk3DWidget::findWaypoint(const QPoint& mousePos) { diff --git a/src/ui/map3D/Pixhawk3DWidget.h b/src/ui/map3D/Pixhawk3DWidget.h index 913875f7c1847dab2bb7e6f7380620c4e7b42282..6087e6328d08acf2c455d0282e9b9ae4e4dfb081 100644 --- a/src/ui/map3D/Pixhawk3DWidget.h +++ b/src/ui/map3D/Pixhawk3DWidget.h @@ -78,10 +78,6 @@ private slots: void setBirdEyeView(void); void loadTerrainModel(void); -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - void addOverlay(UASInterface* uas); -#endif - void selectTargetHeading(void); void selectTarget(void); void setTarget(void); @@ -162,21 +158,6 @@ private: QMap& trailIndexMap); void updateWaypoints(UASInterface* uas, MAV_FRAME frame, osg::ref_ptr& waypointGroupNode); -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - void updateRGBD(UASInterface* uas, MAV_FRAME frame, - osg::ref_ptr& rgbImageNode, - osg::ref_ptr& depthImageNode); - void updatePointCloud(UASInterface* uas, MAV_FRAME frame, - double robotX, double robotY, double robotZ, - osg::ref_ptr& pointCloudNode, - bool colorPointCloudByDistance); - void updateObstacles(UASInterface* uas, MAV_FRAME frame, - double robotX, double robotY, double robotZ, - osg::ref_ptr& obstacleGroupNode); - void updatePlannedPath(UASInterface* uas, MAV_FRAME frame, - double robotX, double robotY, double robotZ, - osg::ref_ptr& plannedPathNode); -#endif int findWaypoint(const QPoint& mousePos); bool findTarget(int mouseX, int mouseY); diff --git a/src/ui/map3D/SystemContainer.cc b/src/ui/map3D/SystemContainer.cc index f74d81e0759c669069b9680e6c5b32e7418867a4..474fd927338a3a255014efa12db4cacb3cf77bf0 100644 --- a/src/ui/map3D/SystemContainer.cc +++ b/src/ui/map3D/SystemContainer.cc @@ -96,25 +96,3 @@ SystemContainer::waypointGroupNode(void) { return mWaypointGroupNode; } - -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - -osg::ref_ptr& -SystemContainer::obstacleGroupNode(void) -{ - return mObstacleGroupNode; -} - -QMap >& -SystemContainer::overlayNodeMap(void) -{ - return mOverlayNodeMap; -} - -osg::ref_ptr& -SystemContainer::plannedPathNode(void) -{ - return mPlannedPathNode; -} - -#endif diff --git a/src/ui/map3D/SystemContainer.h b/src/ui/map3D/SystemContainer.h index dfee5391bbe38e7c236aca67924942c3ed3ed57b..45f72378232bbb10be77a64409498d751ab91fcc 100644 --- a/src/ui/map3D/SystemContainer.h +++ b/src/ui/map3D/SystemContainer.h @@ -10,11 +10,6 @@ #include "ImageWindowGeode.h" #include "WaypointGroupNode.h" -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) -#include "GLOverlayGeode.h" -#include "ObstacleGroupNode.h" -#endif - class SystemContainer { public: @@ -39,11 +34,6 @@ public: osg::ref_ptr& targetNode(void); osg::ref_ptr& trailNode(void); osg::ref_ptr& waypointGroupNode(void); -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - osg::ref_ptr& obstacleGroupNode(void); - QMap >& overlayNodeMap(void); - osg::ref_ptr& plannedPathNode(void); -#endif private: QVector3D mGPSLocalOrigin; @@ -66,11 +56,6 @@ private: osg::ref_ptr mTargetNode; osg::ref_ptr mTrailNode; osg::ref_ptr mWaypointGroupNode; -#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) - osg::ref_ptr mObstacleGroupNode; - QMap > mOverlayNodeMap; - osg::ref_ptr mPlannedPathNode; -#endif }; #endif // SYSTEMCONTAINER_H diff --git a/src/ui/watchdog/WatchdogControl.cc b/src/ui/watchdog/WatchdogControl.cc deleted file mode 100644 index a2682d579aa8b68502be1144aaea5fbe647130d2..0000000000000000000000000000000000000000 --- a/src/ui/watchdog/WatchdogControl.cc +++ /dev/null @@ -1,185 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Implementation of class WatchdogControl - * @author Lorenz Meier - * - */ - -#include "WatchdogControl.h" -#include "WatchdogView.h" -#include "WatchdogProcessView.h" -#include "ui_WatchdogControl.h" -#include "PxQuadMAV.h" - -#include "UASManager.h" - -#include - -WatchdogControl::WatchdogControl(QWidget *parent) : - QWidget(parent), - mav(NULL), - updateInterval(2000000), - ui(new Ui::WatchdogControl) -{ - ui->setupUi(this); - - // UI is initialized, setup layout - listLayout = new QVBoxLayout(ui->mainWidget); - listLayout->setSpacing(6); - listLayout->setMargin(0); - listLayout->setAlignment(Qt::AlignTop); - ui->mainWidget->setLayout(listLayout); - - connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(setUAS(UASInterface*))); - - this->setVisible(false); -} - -WatchdogControl::~WatchdogControl() -{ - delete ui; -} - -void WatchdogControl::setUAS(UASInterface* uas) -{ - PxQuadMAV* qmav = dynamic_cast(uas); - - if (qmav) { - connect(qmav, SIGNAL(processReceived(int,int,int,QString,QString,int)), this, SLOT(addProcess(int,int,int,QString,QString,int))); - connect(qmav, SIGNAL(watchdogReceived(int,int,uint)), this, SLOT(updateWatchdog(int,int,uint))); - connect(qmav, SIGNAL(processChanged(int,int,int,int,bool,int,int)), this, SLOT(updateProcess(int,int,int,int,bool,int,int))); - } -} - -void WatchdogControl::updateWatchdog(int systemId, int watchdogId, unsigned int processCount) -{ - // request the watchdog with the given ID - // Get the watchdog and request the info for it - WatchdogInfo& watchdog = this->getWatchdog(systemId, watchdogId); - - // if the proces count doesn't match, the watchdog is either new or has changed - create a new vector with new (and empty) ProcessInfo structs. - if (watchdog.processes_.size() != processCount) { - watchdog.processes_ = std::vector(processCount); - // Create new UI widget - //WatchdogView* view = new WatchdogView(this); - - } - - // start the timeout timer - //watchdog.timeoutTimer_.reset(); - - qDebug() << "WATCHDOG RECEIVED"; - //qDebug() << "<-- received mavlink_watchdog_heartbeat_t " << msg->sysid << " / " << payload.watchdog_id << " / " << payload.process_count << std::endl; -} - -void WatchdogControl::addProcess(int systemId, int watchdogId, int processId, QString name, QString arguments, int timeout) -{ - // request the watchdog and the process with the given IDs - WatchdogInfo& watchdog = this->getWatchdog(systemId, watchdogId); - ProcessInfo& process = watchdog.getProcess(processId); - - // store the process information in the ProcessInfo struct - process.name_ = name.toStdString(); - process.arguments_ = arguments.toStdString(); - process.timeout_ = timeout; - qDebug() << "PROCESS RECEIVED"; - qDebug() << "SYS" << systemId << "WD" << watchdogId << "PROCESS" << processId << name << "ARG" << arguments << "TO" << timeout; - //qDebug() << "<-- received mavlink_watchdog_process_info_t " << msg->sysid << " / " << (const char*)payload.name << " / " << (const char*)payload.arguments << " / " << payload.timeout << std::endl; -} - - -void WatchdogControl::updateProcess(int systemId, int watchdogId, int processId, int state, bool muted, int crashes, int pid) -{ - // request the watchdog and the process with the given IDs - WatchdogInfo& watchdog = this->getWatchdog(systemId, watchdogId); - ProcessInfo& process = watchdog.getProcess(processId); - - // store the status information in the ProcessInfo struct - process.state_ = static_cast(state); - process.muted_ = muted; - process.crashes_ = crashes; - process.pid_ = pid; - - qDebug() << "PROCESS UPDATED"; - qDebug() << "SYS" << systemId << "WD" << watchdogId << "PROCESS" << processId << "STATE" << state << "CRASH" << crashes << "PID" << pid; - - //process.updateTimer_.reset(); - //qDebug() << "<-- received mavlink_watchdog_process_status_t " << msg->sysid << " / " << payload.state << " / " << payload.muted << " / " << payload.crashes << " / " << payload.pid << std::endl; -} - -/** - @brief Returns a WatchdogInfo struct that belongs to the watchdog with the given system-ID and watchdog-ID -*/ -WatchdogControl::WatchdogInfo& WatchdogControl::getWatchdog(uint8_t systemId, uint16_t watchdogId) -{ - WatchdogID id(systemId, watchdogId); - - std::map::iterator it = this->watchdogs_.find(id); - if (it != this->watchdogs_.end()) { - // the WatchdogInfo struct already exists in the map, return it - return it->second; - } else { - // the WatchdogInfo struct doesn't exist - request info and status for all processes and create the struct - this->sendCommand(id, WatchdogControl::ALL, Command::RequestInfo); - this->sendCommand(id, WatchdogControl::ALL, Command::RequestStatus); - return this->watchdogs_[id]; - } -} - -/** - @brief Returns a ProcessInfo struct that belongs to the process with the given ID. -*/ -WatchdogControl::ProcessInfo& WatchdogControl::WatchdogInfo::getProcess(uint16_t index) -{ - // if the index is out of bounds, resize the vector - if (index >= this->processes_.size()) - this->processes_.resize(index + 1); - - return this->processes_[index]; -} - -/** - @brief Sends a watchdog command to a process on a given watchdog. - @param w_id The WatchdogID struct (containing system-ID and watchdog-ID) that identifies the watchdog - @param p_id The process-ID - @param command The command-ID -*/ -void WatchdogControl::sendCommand(const WatchdogID& w_id, uint16_t p_id, Command::Enum command) -{ - emit sendProcessCommand(w_id.watchdog_id_, p_id, command); -} - -void WatchdogControl::changeEvent(QEvent *e) -{ - QWidget::changeEvent(e); - switch (e->type()) { - case QEvent::LanguageChange: - ui->retranslateUi(this); - break; - default: - break; - } -} diff --git a/src/ui/watchdog/WatchdogControl.h b/src/ui/watchdog/WatchdogControl.h deleted file mode 100644 index 376f9c72a3186d9f3b631dc3f7c5985f8e788037..0000000000000000000000000000000000000000 --- a/src/ui/watchdog/WatchdogControl.h +++ /dev/null @@ -1,175 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Definition of class WatchdogControl - * @author Lorenz Meier - * - */ - -#ifndef WATCHDOGCONTROL_H -#define WATCHDOGCONTROL_H - -#include - -#include -#include -#include - -#include -#include -#include - -#include "WatchdogView.h" - -#include "UASInterface.h" - -namespace Ui -{ -class WatchdogControl; -} - -/** - * @brief Overall widget for controlling all watchdogs of all connected MAVs - */ -class WatchdogControl : public QWidget -{ - Q_OBJECT -public: - - - ///! Command codes, used to send and receive commands over lcm - struct Command { - enum Enum { - Start = 0, - Restart = 1, - Stop = 2, - Mute = 3, - Unmute = 4, - - RequestInfo = 254, - RequestStatus = 255 - }; - }; - - ///! This struct represents a process on the watchdog. Used to store all values. - struct ProcessInfo { - ///! Process state - each process is in exactly one of those states (except unknown, that's just to initialize it) - struct State { - enum Enum { - Unknown = 0, - Running = 1, - Stopped = 2, - Stopped_OK = 3, - Stopped_ERROR = 4 - }; - }; - - ///! Constructor - initialize the values - ProcessInfo() : timeout_(0), state_(State::Unknown), muted_(false), crashes_(0), pid_(-1) {} - - std::string name_; ///< The name of the process - std::string arguments_; ///< The arguments (argv of the process) - - int32_t timeout_; ///< Heartbeat timeout value (in microseconds) - - State::Enum state_; ///< The current state of the process - bool muted_; ///< True if the process is currently muted - uint16_t crashes_; ///< The number of crashes - int32_t pid_; ///< The PID of the process - - //quint64_t requestTimeout; - // Timer requestTimer_; ///< Internal timer, used to repeat status and info requests after some time (in case of packet loss) - // Timer updateTimer_; ///< Internal timer, used to measure the time since the last update (used only for graphics) - }; - - ///! This struct identifies a watchdog. It's a combination of system-ID and watchdog-ID. implements operator< to be used as key in a std::map - struct WatchdogID { - ///! Constructor - initialize the values - WatchdogID(uint8_t system_id, uint16_t watchdog_id) : system_id_(system_id), watchdog_id_(watchdog_id) {} - - uint8_t system_id_; ///< The system-ID - uint16_t watchdog_id_; ///< The watchdog-ID - - ///! Comparison operator which is used by std::map - inline bool operator<(const WatchdogID& other) const { - return (this->system_id_ != other.system_id_) ? (this->system_id_ < other.system_id_) : (this->watchdog_id_ < other.watchdog_id_); - } - - }; - - ///! This struct represents a watchdog - struct WatchdogInfo { - ProcessInfo& getProcess(uint16_t index); - - std::vector processes_; ///< A vector containing all processes running on this watchdog - uint64_t timeout; - QTimer* timeoutTimer_; ///< Internal timer, used to measure the time since the last heartbeat message - }; - - WatchdogControl(QWidget *parent = 0); - ~WatchdogControl(); - - static const uint16_t ALL = (uint16_t)-1; ///< A magic value for a process-ID which addresses "all processes" - static const uint16_t ALL_RUNNING = (uint16_t)-2; ///< A magic value for a process-ID which addresses "all running processes" - static const uint16_t ALL_CRASHED = (uint16_t)-3; ///< A magic value for a process-ID which addresses "all crashed processes" - -public slots: - void updateWatchdog(int systemId, int watchdogId, unsigned int processCount); - void addProcess(int systemId, int watchdogId, int processId, QString name, QString arguments, int timeout); - void updateProcess(int systemId, int watchdogId, int processId, int state, bool muted, int crashed, int pid); - void setUAS(UASInterface* uas); - -signals: - void sendProcessCommand(int watchdogId, int processId, unsigned int command); - -protected: - void changeEvent(QEvent *e); - - UASInterface* mav; - QVBoxLayout* listLayout; - uint64_t updateInterval; - -private: - Ui::WatchdogControl *ui; - - void sendCommand(const WatchdogID& w_id, uint16_t p_id, Command::Enum command); - - WatchdogInfo& getWatchdog(uint8_t system_id, uint16_t watchdog_id); - - std::map watchdogs_; ///< A map containing all watchdogs which are currently active - std::map views; - QTimer updateTimer_; -}; - -#endif // WATCHDOGCONTROL_H - -///! Convert a value to std::string -template -std::string convertToString(T value) -{ - std::ostringstream oss; - oss << value; - return oss.str(); -} diff --git a/src/ui/watchdog/WatchdogControl.ui b/src/ui/watchdog/WatchdogControl.ui deleted file mode 100644 index 1da77133d8dd10ec59e7752ddbdd83d8b0e1bbe2..0000000000000000000000000000000000000000 --- a/src/ui/watchdog/WatchdogControl.ui +++ /dev/null @@ -1,31 +0,0 @@ - - - WatchdogControl - - - - 0 - 0 - 400 - 300 - - - - Form - - - - - - - - - 0 Processes Core 1: 0% Core 2: 0% - - - - - - - - diff --git a/src/ui/watchdog/WatchdogProcessView.cc b/src/ui/watchdog/WatchdogProcessView.cc deleted file mode 100644 index e9c3c1205875559ce1c7917fd23f9b22765149d0..0000000000000000000000000000000000000000 --- a/src/ui/watchdog/WatchdogProcessView.cc +++ /dev/null @@ -1,57 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Implementation of class WatchdogControl - * @author Lorenz Meier - * - */ - -#include "WatchdogProcessView.h" -#include "ui_WatchdogProcessView.h" - -WatchdogProcessView::WatchdogProcessView(int processid, QWidget *parent) : - QWidget(parent), - processid(processid), - m_ui(new Ui::WatchdogProcessView) -{ - m_ui->setupUi(this); -} - -WatchdogProcessView::~WatchdogProcessView() -{ - delete m_ui; -} - -void WatchdogProcessView::changeEvent(QEvent *e) -{ - QWidget::changeEvent(e); - switch (e->type()) { - case QEvent::LanguageChange: - m_ui->retranslateUi(this); - break; - default: - break; - } -} diff --git a/src/ui/watchdog/WatchdogProcessView.h b/src/ui/watchdog/WatchdogProcessView.h deleted file mode 100644 index 2cc9c4a12ce4a1fba8684a8eecdcdf187026c201..0000000000000000000000000000000000000000 --- a/src/ui/watchdog/WatchdogProcessView.h +++ /dev/null @@ -1,60 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Definition of class WatchdogProcessView - * @author Lorenz Meier - * - */ - -#ifndef WATCHDOGPROCESSVIEW_H -#define WATCHDOGPROCESSVIEW_H - -#include -#include - -namespace Ui -{ -class WatchdogProcessView; -} - -/** - * @brief Represents one process monitored by the linux onboard watchdog - */ -class WatchdogProcessView : public QWidget -{ - Q_OBJECT -public: - WatchdogProcessView(int processid, QWidget *parent = 0); - ~WatchdogProcessView(); - -protected: - void changeEvent(QEvent *e); - int processid; - -private: - Ui::WatchdogProcessView *m_ui; -}; - -#endif // WATCHDOGPROCESSVIEW_H diff --git a/src/ui/watchdog/WatchdogProcessView.ui b/src/ui/watchdog/WatchdogProcessView.ui deleted file mode 100644 index ac883b4a7499a07b3dbb0a1193d47c417c72357e..0000000000000000000000000000000000000000 --- a/src/ui/watchdog/WatchdogProcessView.ui +++ /dev/null @@ -1,56 +0,0 @@ - - - WatchdogProcessView - - - - 0 - 0 - 400 - 44 - - - - Form - - - - - - TextLabel - - - - - - - TextLabel - - - - - - - TextLabel - - - - - - - ... - - - - - - - ... - - - - - - - - diff --git a/src/ui/watchdog/WatchdogView.cc b/src/ui/watchdog/WatchdogView.cc deleted file mode 100644 index 60585a6eb0a71e7b8dcdf45d4078ef4bb486b1a6..0000000000000000000000000000000000000000 --- a/src/ui/watchdog/WatchdogView.cc +++ /dev/null @@ -1,56 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Implementation of class WatchdogControl - * @author Lorenz Meier - * - */ - -#include "WatchdogView.h" -#include "ui_WatchdogView.h" - -WatchdogView::WatchdogView(QWidget *parent) : - QWidget(parent), - m_ui(new Ui::WatchdogView) -{ - m_ui->setupUi(this); -} - -WatchdogView::~WatchdogView() -{ - delete m_ui; -} - -void WatchdogView::changeEvent(QEvent *e) -{ - QWidget::changeEvent(e); - switch (e->type()) { - case QEvent::LanguageChange: - m_ui->retranslateUi(this); - break; - default: - break; - } -} diff --git a/src/ui/watchdog/WatchdogView.h b/src/ui/watchdog/WatchdogView.h deleted file mode 100644 index 4dbabf3925141ddf10eda12e85a009ca3dc6db59..0000000000000000000000000000000000000000 --- a/src/ui/watchdog/WatchdogView.h +++ /dev/null @@ -1,58 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Definition of class WatchdogView - * @author Lorenz Meier - * - */ - -#ifndef WATCHDOGVIEW_H -#define WATCHDOGVIEW_H - -#include - -namespace Ui -{ -class WatchdogView; -} - -/** - * @brief Represents one onboard watchdog - */ -class WatchdogView : public QWidget -{ - Q_OBJECT -public: - WatchdogView(QWidget *parent = 0); - ~WatchdogView(); - -protected: - void changeEvent(QEvent *e); - -private: - Ui::WatchdogView *m_ui; -}; - -#endif // WATCHDOGVIEW_H diff --git a/src/ui/watchdog/WatchdogView.ui b/src/ui/watchdog/WatchdogView.ui deleted file mode 100644 index fed4dff83b6d79cc7545998e7e8c673834a73f7b..0000000000000000000000000000000000000000 --- a/src/ui/watchdog/WatchdogView.ui +++ /dev/null @@ -1,31 +0,0 @@ - - - WatchdogView - - - - 0 - 0 - 400 - 300 - - - - Form - - - - - - Watchdog - - - - - - - - - - -