Skip to content
Snippets Groups Projects
UAS.cc 130 KiB
Newer Older
  • Learn to ignore specific revisions
  •         }
                break;
            case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
            {
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
    
    
                const unsigned int portWidth = 8; // XXX magic number
    
    
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
    
                if (channels.chan1_raw != UINT16_MAX)
                    emit remoteControlChannelRawChanged(channels.port * portWidth + 0, channels.chan1_raw);
                if (channels.chan2_raw != UINT16_MAX)
                    emit remoteControlChannelRawChanged(channels.port * portWidth + 1, channels.chan2_raw);
                if (channels.chan3_raw != UINT16_MAX)
                    emit remoteControlChannelRawChanged(channels.port * portWidth + 2, channels.chan3_raw);
                if (channels.chan4_raw != UINT16_MAX)
                    emit remoteControlChannelRawChanged(channels.port * portWidth + 3, channels.chan4_raw);
                if (channels.chan5_raw != UINT16_MAX)
                    emit remoteControlChannelRawChanged(channels.port * portWidth + 4, channels.chan5_raw);
                if (channels.chan6_raw != UINT16_MAX)
                    emit remoteControlChannelRawChanged(channels.port * portWidth + 5, channels.chan6_raw);
                if (channels.chan7_raw != UINT16_MAX)
                    emit remoteControlChannelRawChanged(channels.port * portWidth + 6, channels.chan7_raw);
                if (channels.chan8_raw != UINT16_MAX)
                    emit remoteControlChannelRawChanged(channels.port * portWidth + 7, channels.chan8_raw);
    
            }
                break;
            case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
            {
                mavlink_rc_channels_scaled_t channels;
                mavlink_msg_rc_channels_scaled_decode(&message, &channels);
    
    
                const unsigned int portWidth = 8; // XXX magic number
    
    
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
    
                if (static_cast<uint16_t>(channels.chan1_scaled) != UINT16_MAX)
    
                    emit remoteControlChannelScaledChanged(channels.port * portWidth + 0, channels.chan1_scaled/10000.0f);
    
                if (static_cast<uint16_t>(channels.chan2_scaled) != UINT16_MAX)
    
                    emit remoteControlChannelScaledChanged(channels.port * portWidth + 1, channels.chan2_scaled/10000.0f);
    
                if (static_cast<uint16_t>(channels.chan3_scaled) != UINT16_MAX)
    
                    emit remoteControlChannelScaledChanged(channels.port * portWidth + 2, channels.chan3_scaled/10000.0f);
    
                if (static_cast<uint16_t>(channels.chan4_scaled) != UINT16_MAX)
    
                    emit remoteControlChannelScaledChanged(channels.port * portWidth + 3, channels.chan4_scaled/10000.0f);
    
                if (static_cast<uint16_t>(channels.chan5_scaled) != UINT16_MAX)
    
                    emit remoteControlChannelScaledChanged(channels.port * portWidth + 4, channels.chan5_scaled/10000.0f);
    
                if (static_cast<uint16_t>(channels.chan6_scaled) != UINT16_MAX)
    
                    emit remoteControlChannelScaledChanged(channels.port * portWidth + 5, channels.chan6_scaled/10000.0f);
    
                if (static_cast<uint16_t>(channels.chan7_scaled) != UINT16_MAX)
    
                    emit remoteControlChannelScaledChanged(channels.port * portWidth + 6, channels.chan7_scaled/10000.0f);
    
                if (static_cast<uint16_t>(channels.chan8_scaled) != UINT16_MAX)
    
                    emit remoteControlChannelScaledChanged(channels.port * portWidth + 7, channels.chan8_scaled/10000.0f);
    
            }
                break;
            case MAVLINK_MSG_ID_PARAM_VALUE:
            {
    
                mavlink_param_value_t rawValue;
                mavlink_msg_param_value_decode(&message, &rawValue);
                QByteArray bytes(rawValue.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
    
                // Construct a string stopping at the first NUL (0) character, else copy the whole
                // byte array (max MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN, so safe)
                QString parameterName(bytes);
    
                mavlink_param_union_t paramVal;
                paramVal.param_float = rawValue.param_value;
                paramVal.type = rawValue.param_type;
    
                processParamValueMsg(message, parameterName,rawValue,paramVal);
    
                break;
            case MAVLINK_MSG_ID_COMMAND_ACK:
            {
                mavlink_command_ack_t ack;
                mavlink_msg_command_ack_decode(&message, &ack);
                switch (ack.result)
                {
                case MAV_RESULT_ACCEPTED:
                {
                    emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
                }
                    break;
                case MAV_RESULT_TEMPORARILY_REJECTED:
                {
                    emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Temporarily rejected CMD: %1").arg(ack.command));
                }
                    break;
                case MAV_RESULT_DENIED:
                {
                    emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Denied CMD: %1").arg(ack.command));
                }
                    break;
                case MAV_RESULT_UNSUPPORTED:
                {
                    emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Unsupported CMD: %1").arg(ack.command));
                }
                    break;
                case MAV_RESULT_FAILED:
                {
                    emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Failed CMD: %1").arg(ack.command));
                }
                    break;
                }
            }
            case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
            {
                mavlink_roll_pitch_yaw_thrust_setpoint_t out;
                mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
                quint64 time = getUnixTimeFromMs(out.time_boot_ms);
                emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
            }
                break;
            case MAVLINK_MSG_ID_MISSION_COUNT:
            {
                mavlink_mission_count_t wpc;
                mavlink_msg_mission_count_decode(&message, &wpc);
                if(wpc.target_system == mavlink->getSystemId() || wpc.target_system == 0)
                {
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
                else
                {
                    qDebug() << "Got waypoint message, but was wrong system id" << wpc.target_system;
                }
            }
                break;
    
            case MAVLINK_MSG_ID_MISSION_ITEM:
            {
                mavlink_mission_item_t wp;
                mavlink_msg_mission_item_decode(&message, &wp);
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
                if(wp.target_system == mavlink->getSystemId() || wp.target_system == 0)
                {
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
                else
                {
                    qDebug() << "Got waypoint message, but was wrong system id" << wp.target_system;
                }
            }
                break;
    
            case MAVLINK_MSG_ID_MISSION_ACK:
            {
                mavlink_mission_ack_t wpa;
                mavlink_msg_mission_ack_decode(&message, &wpa);
                if((wpa.target_system == mavlink->getSystemId() || wpa.target_system == 0) &&
                        (wpa.target_component == mavlink->getComponentId() || wpa.target_component == 0))
                {
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
            }
                break;
    
            case MAVLINK_MSG_ID_MISSION_REQUEST:
            {
                mavlink_mission_request_t wpr;
                mavlink_msg_mission_request_decode(&message, &wpr);
                if(wpr.target_system == mavlink->getSystemId() || wpr.target_system == 0)
                {
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
                else
                {
                    qDebug() << "Got waypoint message, but was wrong system id" << wpr.target_system;
                }
            }
                break;
    
            case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
            {
                mavlink_mission_item_reached_t wpr;
                mavlink_msg_mission_item_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
                QString text = QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq);
                GAudioOutput::instance()->say(text);
                emit textMessageReceived(message.sysid, message.compid, 0, text);
            }
                break;
    
            case MAVLINK_MSG_ID_MISSION_CURRENT:
            {
                mavlink_mission_current_t wpc;
                mavlink_msg_mission_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
                break;
    
            case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
                if (multiComponentSourceDetected && wrongComponent)
                {
                    break;
                }
                mavlink_local_position_setpoint_t p;
                mavlink_msg_local_position_setpoint_decode(&message, &p);
                emit positionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw, QGC::groundTimeUsecs());
            }
                break;
            case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
            {
                mavlink_set_local_position_setpoint_t p;
                mavlink_msg_set_local_position_setpoint_decode(&message, &p);
                emit userPositionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw);
            }
                break;
            case MAVLINK_MSG_ID_STATUSTEXT:
            {
                QByteArray b;
    
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
    
                mavlink_msg_statustext_get_text(&message, b.data());
    
                // Ensure NUL-termination
                b[b.length()-1] = '\0';
    
                QString text = QString(b);
                int severity = mavlink_msg_statustext_get_severity(&message);
    
                if (text.startsWith("#audio:"))
                {
                    text.remove("#audio:");
                    emit textMessageReceived(uasId, message.compid, severity, QString("Audio message: ") + text);
                    GAudioOutput::instance()->say(text, severity);
                }
                else
                {
                    emit textMessageReceived(uasId, message.compid, severity, text);
                }
            }
                break;
    
            case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
            {
                mavlink_servo_output_raw_t raw;
                mavlink_msg_servo_output_raw_decode(&message, &raw);
    
    
                if (hilEnabled && raw.port == 0)
    
    Lorenz Meier's avatar
    Lorenz Meier committed
                    emit hilActuatorsChanged(static_cast<uint64_t>(getUnixTimeFromMs(raw.time_usec)), static_cast<float>(raw.servo1_raw),
    
                                         static_cast<float>(raw.servo2_raw), static_cast<float>(raw.servo3_raw),
                                         static_cast<float>(raw.servo4_raw), static_cast<float>(raw.servo5_raw), static_cast<float>(raw.servo6_raw),
                                         static_cast<float>(raw.servo7_raw), static_cast<float>(raw.servo8_raw));
                }
            }
            break;
    
    #ifdef MAVLINK_ENABLED_PIXHAWK
            case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
                mavlink_data_transmission_handshake_t p;
                mavlink_msg_data_transmission_handshake_decode(&message, &p);
                imageSize = p.size;
                imagePackets = p.packets;
                imagePayload = p.payload;
                imageQuality = p.jpg_quality;
                imageType = p.type;
                imageWidth = p.width;
                imageHeight = p.height;
                imageStart = QGC::groundTimeMilliseconds();
    
                imagePacketsArrived = 0;
    
    
            }
                break;
    
            case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
                mavlink_encapsulated_data_t img;
                mavlink_msg_encapsulated_data_decode(&message, &img);
                int seq = img.seqnr;
                int pos = seq * imagePayload;
    
                // Check if we have a valid transaction
                if (imagePackets == 0)
                {
                    // NO VALID TRANSACTION - ABORT
                    // Restart statemachine
                    imagePacketsArrived = 0;
                }
    
                for (int i = 0; i < imagePayload; ++i)
                {
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
    
                ++imagePacketsArrived;
    
                // emit signal if all packets arrived
                if ((imagePacketsArrived >= imagePackets))
                {
                    // Restart statemachine
                    emit imageReady(this);
                    //qDebug() << "imageReady emitted. all packets arrived";
                }
            }
                break;
    
    
    
    #endif
                //        case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT:
                //        {
                //            mavlink_object_detection_event_t event;
                //            mavlink_msg_object_detection_event_decode(&message, &event);
                //            QString str(event.name);
                //            emit objectDetected(event.time, event.object_id, event.type, str, event.quality, event.bearing, event.distance);
                //        }
                //        break;
                // WILL BE ENABLED ONCE MESSAGE IS IN COMMON MESSAGE SET
                //        case MAVLINK_MSG_ID_MEMORY_VECT:
                //        {
                //            mavlink_memory_vect_t vect;
                //            mavlink_msg_memory_vect_decode(&message, &vect);
                //            QString str("mem_%1");
                //            quint64 time = getUnixTime(0);
                //            int16_t *mem0 = (int16_t *)&vect.value[0];
                //            uint16_t *mem1 = (uint16_t *)&vect.value[0];
                //            int32_t *mem2 = (int32_t *)&vect.value[0];
                //            // uint32_t *mem3 = (uint32_t *)&vect.value[0]; causes overload problem
                //            float *mem4 = (float *)&vect.value[0];
                //            if ( vect.ver == 0) vect.type = 0, vect.ver = 1; else ;
                //            if ( vect.ver == 1)
                //            {
                //                switch (vect.type) {
                //                default:
                //                case 0:
                //                    for (int i = 0; i < 16; i++)
                //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
                //                    break;
                //                case 1:
                //                    for (int i = 0; i < 16; i++)
                //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
                //                    break;
                //                case 2:
                //                    for (int i = 0; i < 16; i++)
                //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time);
                //                    break;
                //                case 3:
                //                    for (int i = 0; i < 16; i++)
                //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time);
                //                    break;
                //                case 4:
                //                    for (int i = 0; i < 8; i++)
                //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
                //                    break;
                //                case 5:
                //                    for (int i = 0; i < 8; i++)
                //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
                //                    break;
                //                case 6:
                //                    for (int i = 0; i < 8; i++)
                //                        // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
                //                    break;
                //                }
                //            }
                //        }
                //        break;
    #ifdef MAVLINK_ENABLED_UALBERTA
            case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
                mavlink_nav_filter_bias_t bias;
                mavlink_msg_nav_filter_bias_decode(&message, &bias);
                quint64 time = getUnixTime();
                // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time);
                // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time);
                // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time);
                // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time);
                // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time);
                // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time);
            }
                break;
            case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
                QVector<uint16_t> aileron;
                QVector<uint16_t> elevator;
                QVector<uint16_t> rudder;
                QVector<uint16_t> gyro;
                QVector<uint16_t> pitch;
                QVector<uint16_t> throttle;
    
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN; ++i)
                    aileron << radioMsg.aileron[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN; ++i)
                    elevator << radioMsg.elevator[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN; ++i)
                    rudder << radioMsg.rudder[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN; ++i)
                    gyro << radioMsg.gyro[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN; ++i)
                    pitch << radioMsg.pitch[i];
                for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN; ++i)
                    throttle << radioMsg.throttle[i];
    
                QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
                emit radioCalibrationReceived(radioData);
                delete radioData;
            }
                break;
    
    #endif
                // Messages to ignore
            case MAVLINK_MSG_ID_RAW_IMU:
            case MAVLINK_MSG_ID_SCALED_IMU:
            case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
    
            {
                //mavlink_set_local_position_setpoint_t p;
                //mavlink_msg_set_local_position_setpoint_decode(&message, &p);
                //emit userPositionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw);
                mavlink_nav_controller_output_t p;
                mavlink_msg_nav_controller_output_decode(&message,&p);
                setDistToWaypoint(p.wp_dist);
    
                setBearingToWaypoint(p.nav_bearing);
                //setAltitudeError(p.alt_error);
                //setSpeedError(p.aspd_error);
                //setCrosstrackingError(p.xtrack_error);
                emit navigationControllerErrorsChanged(this, p.alt_error, p.aspd_error, p.xtrack_error);
    
            case MAVLINK_MSG_ID_RAW_PRESSURE:
            case MAVLINK_MSG_ID_SCALED_PRESSURE:
            case MAVLINK_MSG_ID_OPTICAL_FLOW:
            case MAVLINK_MSG_ID_DEBUG_VECT:
            case MAVLINK_MSG_ID_DEBUG:
            case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
            case MAVLINK_MSG_ID_NAMED_VALUE_INT:
            case MAVLINK_MSG_ID_MANUAL_CONTROL:
            case MAVLINK_MSG_ID_HIGHRES_IMU:
                break;
            default:
            {
                if (!unknownPackets.contains(message.msgid))
                {
                    unknownPackets.append(message.msgid);
    
    Lorenz Meier's avatar
    Lorenz Meier committed
                    emit unknownPacketReceived(uasId, message.compid, message.msgid);
    
    Lorenz Meier's avatar
    Lorenz Meier committed
                    qWarning() << "Unknown message from system:" << uasId << "message:" << message.msgid;
    
                }
            }
                break;
            }
        }
    }
    
    
    #if defined(QGC_PROTOBUF_ENABLED)
    /**
    * Receive an extended message.
    * @param link
    * @param message
    */
    void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message)
    {
        if (!link)
        {
            return;
        }
        if (!links->contains(link))
        {
            addLink(link);
        }
    
        const google::protobuf::Descriptor* descriptor = message->GetDescriptor();
        if (!descriptor)
        {
            return;
        }
    
        const google::protobuf::FieldDescriptor* headerField = descriptor->FindFieldByName("header");
        if (!headerField)
        {
            return;
        }
    
        const google::protobuf::Descriptor* headerDescriptor = headerField->message_type();
        if (!headerDescriptor)
        {
            return;
        }
    
        const google::protobuf::FieldDescriptor* sourceSysIdField = headerDescriptor->FindFieldByName("source_sysid");
        if (!sourceSysIdField)
        {
            return;
        }
    
        const google::protobuf::Reflection* reflection = message->GetReflection();
        const google::protobuf::Message& headerMsg = reflection->GetMessage(*message, headerField);
        const google::protobuf::Reflection* headerReflection = headerMsg.GetReflection();
    
        int source_sysid = headerReflection->GetInt32(headerMsg, sourceSysIdField);
    
        if (source_sysid != uasId)
        {
            return;
        }
    
    #ifdef QGC_USE_PIXHAWK_MESSAGES
        if (message->GetTypeName() == overlay.GetTypeName())
        {
            receivedOverlayTimestamp = QGC::groundTimeSeconds();
            overlayMutex.lock();
            overlay.CopyFrom(*message);
            overlayMutex.unlock();
            emit overlayChanged(this);
        }
        else if (message->GetTypeName() == obstacleList.GetTypeName())
        {
            receivedObstacleListTimestamp = QGC::groundTimeSeconds();
            obstacleListMutex.lock();
            obstacleList.CopyFrom(*message);
            obstacleListMutex.unlock();
            emit obstacleListChanged(this);
        }
        else if (message->GetTypeName() == path.GetTypeName())
        {
            receivedPathTimestamp = QGC::groundTimeSeconds();
            pathMutex.lock();
            path.CopyFrom(*message);
            pathMutex.unlock();
            emit pathChanged(this);
        }
        else if (message->GetTypeName() == pointCloud.GetTypeName())
        {
            receivedPointCloudTimestamp = QGC::groundTimeSeconds();
            pointCloudMutex.lock();
            pointCloud.CopyFrom(*message);
            pointCloudMutex.unlock();
            emit pointCloudChanged(this);
        }
        else if (message->GetTypeName() == rgbdImage.GetTypeName())
        {
            receivedRGBDImageTimestamp = QGC::groundTimeSeconds();
            rgbdImageMutex.lock();
            rgbdImage.CopyFrom(*message);
            rgbdImageMutex.unlock();
            emit rgbdImageChanged(this);
        }
    #endif
    }
    
    #endif
    
    /**
    * Set the home position of the UAS.
    * @param lat The latitude fo the home position
    
    * @param lon The longitude of the home position
    
    * @param alt The altitude of the home position
    */
    void UAS::setHomePosition(double lat, double lon, double alt)
    {
    
        if (blockHomePositionChanges)
            return;
    
    
        QString uasName = (getUASName() == "")?
                    tr("UAS") + QString::number(getUASID())
                  : getUASName();
    
    
        QMessageBox msgBox;
        msgBox.setIcon(QMessageBox::Warning);
    
        msgBox.setText(tr("Set a new home position for vehicle %1").arg(uasName));
    
        msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location");
        msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
        msgBox.setDefaultButton(QMessageBox::Cancel);
        int ret = msgBox.exec();
    
        // Close the message box shortly after the click to prevent accidental clicks
        QTimer::singleShot(5000, &msgBox, SLOT(reject()));
    
    
        if (ret == QMessageBox::Yes)
        {
            mavlink_message_t msg;
            mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 0, 0, 0, 0, lat, lon, alt);
            // Send message twice to increase chance that it reaches its goal
            sendMessage(msg);
    
            // Send new home position to UAS
            mavlink_set_gps_global_origin_t home;
            home.target_system = uasId;
            home.latitude = lat*1E7;
            home.longitude = lon*1E7;
            home.altitude = alt*1000;
            qDebug() << "lat:" << home.latitude << " lon:" << home.longitude;
            mavlink_msg_set_gps_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home);
            sendMessage(msg);
    
        } else {
            blockHomePositionChanges = true;
    
        }
    }
    
    /**
    * Set the origin to the current GPS location.
    **/
    void UAS::setLocalOriginAtCurrentGPSPosition()
    {
        QMessageBox msgBox;
        msgBox.setIcon(QMessageBox::Warning);
    
        msgBox.setText("Set the home position at the current GPS position?");
    
        msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location");
        msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
        msgBox.setDefaultButton(QMessageBox::Cancel);
        int ret = msgBox.exec();
    
        // Close the message box shortly after the click to prevent accidental clicks
        QTimer::singleShot(5000, &msgBox, SLOT(reject()));
    
    
        if (ret == QMessageBox::Yes)
        {
            mavlink_message_t msg;
            mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_DO_SET_HOME, 1, 1, 0, 0, 0, 0, 0, 0);
            // Send message twice to increase chance that it reaches its goal
            sendMessage(msg);
        }
    }
    
    /**
    * Set a local position setpoint.
    * @param x postion
    * @param y position
    * @param z position
    
    void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
    {
    #ifdef MAVLINK_ENABLED_PIXHAWK
        mavlink_message_t msg;
        mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw/M_PI*180.0);
        sendMessage(msg);
    #else
        Q_UNUSED(x);
        Q_UNUSED(y);
        Q_UNUSED(z);
        Q_UNUSED(yaw);
    #endif
    }
    
    /**
    * Set a offset of the local position.
    * @param x position
    * @param y position
    * @param z position
    
    */
    void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
    {
    #ifdef MAVLINK_ENABLED_PIXHAWK
        mavlink_message_t msg;
        mavlink_msg_set_position_control_offset_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
        sendMessage(msg);
    #else
        Q_UNUSED(x);
        Q_UNUSED(y);
        Q_UNUSED(z);
        Q_UNUSED(yaw);
    #endif
    }
    
    
    void UAS::startRadioControlCalibration(int param)
    
    {
        mavlink_message_t msg;
        // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
    
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, param, 0, 0, 0);
    
        sendMessage(msg);
    }
    
    void UAS::endRadioControlCalibration()
    {
        mavlink_message_t msg;
        // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 0, 0, 0, 0);
    
        sendMessage(msg);
    }
    
    void UAS::startDataRecording()
    {
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 2, 0, 0, 0);
        sendMessage(msg);
    }
    
    void UAS::stopDataRecording()
    {
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_DO_CONTROL_VIDEO, 1, -1, -1, -1, 0, 0, 0, 0);
        sendMessage(msg);
    }
    
    void UAS::startMagnetometerCalibration()
    {
        mavlink_message_t msg;
        // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 1, 0, 0, 0, 0, 0);
        sendMessage(msg);
    }
    
    void UAS::startGyroscopeCalibration()
    {
        mavlink_message_t msg;
        // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0, 0, 0, 0);
        sendMessage(msg);
    }
    
    void UAS::startPressureCalibration()
    {
        mavlink_message_t msg;
        // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 1, 0, 0, 0, 0);
        sendMessage(msg);
    }
    
    
    /**
    * Check if time is smaller than 40 years, assuming no system without Unix
    
    * timestamp runs longer than 40 years continuously without reboot. In worst case
    * this will add/subtract the communication delay between GCS and MAV, it will
    * never alter the timestamp in a safety critical way.
    */
    quint64 UAS::getUnixReferenceTime(quint64 time)
    {
        // Same as getUnixTime, but does not react to attitudeStamped mode
        if (time == 0)
        {
            //        qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
            return QGC::groundTimeMilliseconds();
        }
        // Check if time is smaller than 40 years,
        // assuming no system without Unix timestamp
        // runs longer than 40 years continuously without
        // reboot. In worst case this will add/subtract the
        // communication delay between GCS and MAV,
        // it will never alter the timestamp in a safety
        // critical way.
        //
        // Calculation:
        // 40 years
        // 365 days
        // 24 hours
        // 60 minutes
        // 60 seconds
        // 1000 milliseconds
        // 1000 microseconds
    #ifndef _MSC_VER
        else if (time < 1261440000000000LLU)
    #else
        else if (time < 1261440000000000)
    #endif
        {
            //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
            if (onboardTimeOffset == 0)
            {
                onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
            }
            return time/1000 + onboardTimeOffset;
        }
        else
        {
            // Time is not zero and larger than 40 years -> has to be
            // a Unix epoch timestamp. Do nothing.
            return time/1000;
        }
    }
    
    /**
    * @warning If attitudeStamped is enabled, this function will not actually return
    
    * the precise time stamp of this measurement augmented to UNIX time, but will
    
    * MOVE the timestamp IN TIME to match the last measured attitude. There is no
    
    * reason why one would want this, except for system setups where the onboard
    
    * clock is not present or broken and datasets should be collected that are still
    
    * roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE
    
    * SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL!
    */
    quint64 UAS::getUnixTimeFromMs(quint64 time)
    {
        return getUnixTime(time*1000);
    }
    
    /**
    * @warning If attitudeStamped is enabled, this function will not actually return
    
    * the precise time stam of this measurement augmented to UNIX time, but will
    * MOVE the timestamp IN TIME to match the last measured attitude. There is no
    * reason why one would want this, except for system setups where the onboard
    * clock is not present or broken and datasets should be collected that are
    
    * still roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED
    * RUINS THE SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL!
    */
    quint64 UAS::getUnixTime(quint64 time)
    {
        quint64 ret = 0;
        if (attitudeStamped)
        {
            ret = lastAttitude;
        }
    
        if (time == 0)
        {
            ret = QGC::groundTimeMilliseconds();
        }
        // Check if time is smaller than 40 years,
        // assuming no system without Unix timestamp
        // runs longer than 40 years continuously without
        // reboot. In worst case this will add/subtract the
        // communication delay between GCS and MAV,
        // it will never alter the timestamp in a safety
        // critical way.
        //
        // Calculation:
        // 40 years
        // 365 days
        // 24 hours
        // 60 minutes
        // 60 seconds
        // 1000 milliseconds
        // 1000 microseconds
    #ifndef _MSC_VER
        else if (time < 1261440000000000LLU)
    #else
        else if (time < 1261440000000000)
    #endif
        {
            //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
            if (onboardTimeOffset == 0 || time < (lastNonNullTime - 100))
            {
                lastNonNullTime = time;
                onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
            }
            if (time > lastNonNullTime) lastNonNullTime = time;
    
            ret = time/1000 + onboardTimeOffset;
        }
        else
        {
            // Time is not zero and larger than 40 years -> has to be
            // a Unix epoch timestamp. Do nothing.
            ret = time/1000;
        }
    
        return ret;
    }
    
    /**
    * @param component that will be searched for in the map of parameters.
    */
    QList<QString> UAS::getParameterNames(int component)
    {
        if (parameters.contains(component))
        {
            return parameters.value(component)->keys();
        }
        else
        {
            return QList<QString>();
        }
    }
    
    QList<int> UAS::getComponentIds()
    {
        return parameters.keys();
    }
    
    /**
    
    * @param newBaseMode that UAS is to be set to.
    * @param newCustomMode that UAS is to be set to.
    
    void UAS::setMode(uint8_t newBaseMode, uint32_t newCustomMode)
    
        if (receivedMode)
        {
            //this->mode = mode; //no call assignament, update receive message from UAS
    
            // Strip armed / disarmed call for safety reasons, this is not relevant for setting the mode
            newBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
            // Now set current state (request no change)
            newBaseMode |= this->base_mode & MAV_MODE_FLAG_SAFETY_ARMED;
    
    //        // Strip HIL part, replace it with current system state
    //        newBaseMode &= (~MAV_MODE_FLAG_HIL_ENABLED);
    //        // Now set current state (request no change)
    //        newBaseMode |= this->base_mode & MAV_MODE_FLAG_HIL_ENABLED;
    
    Thomas Gubler's avatar
    Thomas Gubler committed
            qDebug() << "WARNING: setMode called before base_mode bitmask was received from UAS, new mode was not sent to system";
    
        }
    }
    
    /**
    * @param newBaseMode that UAS is to be set to.
    * @param newCustomMode that UAS is to be set to.
    */
    void UAS::setModeArm(uint8_t newBaseMode, uint32_t newCustomMode)
    {
        if (receivedMode)
        {
            mavlink_message_t msg;
            mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, newBaseMode, newCustomMode);
            qDebug() << "mavlink_msg_set_mode_pack 1";
            sendMessage(msg);
            qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", MODE " << newBaseMode << " " << newCustomMode;
        }
        else
        {
    
    Thomas Gubler's avatar
    Thomas Gubler committed
            qDebug() << "WARNING: setModeArm called before base_mode bitmask was received from UAS, new mode was not sent to system";
    
    }
    
    /**
    * Send a message to every link that is connected.
    * @param message that is to be sent
    */
    void UAS::sendMessage(mavlink_message_t message)
    {
    
        if (!LinkManager::instance())
        {
            qWarning() << "LINKMANAGER NOT AVAILABLE!";
            return;
        }
    
        if (links->count() < 1) {
            qDebug() << "NO LINK AVAILABLE TO SEND!";
        }
    
    
        // Emit message on all links that are currently connected
        foreach (LinkInterface* link, *links)
        {
            if (LinkManager::instance()->getLinks().contains(link))
            {
    
                if (link->isConnected())
                    sendMessage(link, message);
    
            }
            else
            {
                // Remove from list
                links->removeAt(links->indexOf(link));
            }
        }
    }
    
    /**
    * Forward a message to all links that are currently connected.
    * @param message that is to be forwarded
    */
    void UAS::forwardMessage(mavlink_message_t message)
    {
        // Emit message on all links that are currently connected
        QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
    
        foreach(LinkInterface* link, link_list)
        {
            if (link)
            {
                SerialLink* serial = dynamic_cast<SerialLink*>(link);
                if(serial != 0)
                {
                    for(int i=0; i<links->size(); i++)
                    {
                        if(serial != links->at(i))
                        {
    
                            if (link->isConnected()) {
                                qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
                                sendMessage(serial, message);
                            }
    
                        }
                    }
                }
            }
        }
    }
    
    /**
    * Send a message to the link that is connected.
    * @param link that the message will be sent to
    * @message that is to be sent
    */
    void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
    {
        if(!link) return;
        // Create buffer
        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
        // Write message into buffer, prepending start sign
        int len = mavlink_msg_to_send_buffer(buffer, &message);
        static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
        mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]);
    
        // If link is connected
        if (link->isConnected())
        {
            // Send the portion of the buffer now occupied by the message
            link->writeBytes((const char*)buffer, len);
        }
    
        else
        {
            qDebug() << "LINK NOT CONNECTED, NOT SENDING!";
        }