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 8e517dc80a1951ed004b1c3a433a7e5fc8048fa4..510f07f750ece6ed315839b01a8bfec0fe9f6d35 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -245,7 +245,6 @@ INCLUDEPATH += \ src/lib/qmapcontrol \ src/ui/mavlink \ src/ui/param \ - src/ui/watchdog \ src/ui/map3D \ src/ui/mission \ src/ui/designer \ @@ -266,16 +265,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 \ @@ -372,7 +367,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 \ @@ -384,10 +378,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 20c7e629fe5a838abd8aefff00085e248d1f81d2..a359de316da857a3509cfaba8300aff1a3bd8938 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 c6cdc06442b158bb19da4e5e2aace8f94df8a851..3dc49196dd7ed459172f65e1e5d3bb69f44b66e6 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 @@ -1541,25 +1538,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 bdcaaf834a2b99a64a7da1bf5e79269abe111272..8b466037f45ba4d573fce697016462b8e920f2e7 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/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 - - - - - - - - - - -