FollowMe.cc 5.74 KB
Newer Older
Jimmy Johnson's avatar
Jimmy Johnson committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30
/*=====================================================================

 QGroundControl Open Source Ground Control Station
 
 (c) 2009 - 2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 
 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 <http://www.gnu.org/licenses/>.
 
 ======================================================================*/
#include <QElapsedTimer>
#include <cmath>

#include "MultiVehicleManager.h"
#include "PX4FirmwarePlugin.h"
#include "MAVLinkProtocol.h"
#include "FollowMe.h"
#include "Vehicle.h"
Jimmy Johnson's avatar
Jimmy Johnson committed
31
#include "PositionManager.h"
Jimmy Johnson's avatar
Jimmy Johnson committed
32 33

FollowMe::FollowMe(QGCApplication* app)
Jimmy Johnson's avatar
Jimmy Johnson committed
34
    : QGCTool(app), estimatation_capabilities(0)
Jimmy Johnson's avatar
Jimmy Johnson committed
35 36
{
    memset(&_motionReport, 0, sizeof(motionReport_s));
Jimmy Johnson's avatar
Jimmy Johnson committed
37
    runTime.start();
Jimmy Johnson's avatar
Jimmy Johnson committed
38

Jimmy Johnson's avatar
Jimmy Johnson committed
39 40
    _gcsMotionReportTimer.setSingleShot(false);
    connect(&_gcsMotionReportTimer, &QTimer::timeout, this, &FollowMe::_sendGCSMotionReport);
Jimmy Johnson's avatar
Jimmy Johnson committed
41 42 43 44
}

FollowMe::~FollowMe()
{
Jimmy Johnson's avatar
Jimmy Johnson committed
45
    _disable();
Jimmy Johnson's avatar
Jimmy Johnson committed
46 47 48 49 50 51 52 53
}

void FollowMe::followMeHandleManager(const QString&)
{
    QmlObjectListModel & vehicles = *_toolbox->multiVehicleManager()->vehicles();

    for (int i=0; i< vehicles.count(); i++) {
        Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]);
Jimmy Johnson's avatar
Jimmy Johnson committed
54 55
        if(vehicle->flightMode().compare(PX4FirmwarePlugin::followMeFlightMode, Qt::CaseInsensitive) == 0) {
            _enable();
Jimmy Johnson's avatar
Jimmy Johnson committed
56 57 58 59
            return;
        }
    }

Jimmy Johnson's avatar
Jimmy Johnson committed
60
    _disable();
Jimmy Johnson's avatar
Jimmy Johnson committed
61 62
}

Jimmy Johnson's avatar
Jimmy Johnson committed
63
void FollowMe::_enable()
Jimmy Johnson's avatar
Jimmy Johnson committed
64
{
Jimmy Johnson's avatar
Jimmy Johnson committed
65 66 67 68 69 70 71
    connect(_toolbox->qgcPositionManager(),
            SIGNAL(positionInfoUpdated(QGeoPositionInfo)),
            this,
            SLOT(_setGPSLocation(QGeoPositionInfo)));

    _gcsMotionReportTimer.setInterval(_toolbox->qgcPositionManager()->updateInterval());
    _gcsMotionReportTimer.start();
Jimmy Johnson's avatar
Jimmy Johnson committed
72 73
}

Jimmy Johnson's avatar
Jimmy Johnson committed
74
void FollowMe::_disable()
Jimmy Johnson's avatar
Jimmy Johnson committed
75
{
Jimmy Johnson's avatar
Jimmy Johnson committed
76 77 78 79 80 81
    disconnect(_toolbox->qgcPositionManager(),
               SIGNAL(positionInfoUpdated(QGeoPositionInfo)),
               this,
               SLOT(_setGPSLocation(QGeoPositionInfo)));

    _gcsMotionReportTimer.stop();
Jimmy Johnson's avatar
Jimmy Johnson committed
82 83 84 85 86 87 88 89 90 91 92 93 94 95
}

void FollowMe::_setGPSLocation(QGeoPositionInfo geoPositionInfo)
{
    if (geoPositionInfo.isValid())
    {
        // get the current location coordinates

        QGeoCoordinate geoCoordinate = geoPositionInfo.coordinate();

        _motionReport.lat_int = geoCoordinate.latitude()*1e7;
        _motionReport.lon_int = geoCoordinate.longitude()*1e7;
        _motionReport.alt = geoCoordinate.altitude();

Jimmy Johnson's avatar
Jimmy Johnson committed
96 97
        estimatation_capabilities |= (1 << POS);

Jimmy Johnson's avatar
Jimmy Johnson committed
98 99 100 101 102 103 104 105
        // get the current eph and epv

        if(geoPositionInfo.hasAttribute(QGeoPositionInfo::HorizontalAccuracy) == true) {
            _motionReport.pos_std_dev[0] = _motionReport.pos_std_dev[1] = geoPositionInfo.attribute(QGeoPositionInfo::HorizontalAccuracy);
        }

        if(geoPositionInfo.hasAttribute(QGeoPositionInfo::VerticalAccuracy) == true) {
            _motionReport.pos_std_dev[2] = geoPositionInfo.attribute(QGeoPositionInfo::VerticalAccuracy);
Jimmy Johnson's avatar
Jimmy Johnson committed
106
        }                
Jimmy Johnson's avatar
Jimmy Johnson committed
107 108 109 110 111 112 113 114 115 116 117 118

        // calculate z velocity if it's availible

        if(geoPositionInfo.hasAttribute(QGeoPositionInfo::VerticalSpeed)) {
            _motionReport.vz = geoPositionInfo.attribute(QGeoPositionInfo::VerticalSpeed);
        }

        // calculate x,y velocity if it's availible

        if((geoPositionInfo.hasAttribute(QGeoPositionInfo::Direction)   == true) &&
           (geoPositionInfo.hasAttribute(QGeoPositionInfo::GroundSpeed) == true)) {

Jimmy Johnson's avatar
Jimmy Johnson committed
119 120
            estimatation_capabilities |= (1 << VEL);

Jimmy Johnson's avatar
Jimmy Johnson committed
121 122 123 124 125
            qreal direction = _degreesToRadian(geoPositionInfo.attribute(QGeoPositionInfo::Direction));
            qreal velocity = geoPositionInfo.attribute(QGeoPositionInfo::GroundSpeed);

            _motionReport.vx = cos(direction)*velocity;
            _motionReport.vy = sin(direction)*velocity;
Jimmy Johnson's avatar
Jimmy Johnson committed
126 127 128 129

        } else {
            _motionReport.vx = 0.0f;
            _motionReport.vy = 0.0f;
Jimmy Johnson's avatar
Jimmy Johnson committed
130 131 132 133 134 135 136 137 138 139 140 141 142
        }
    }
}

void FollowMe::_sendGCSMotionReport(void)
{
    QmlObjectListModel & vehicles = *_toolbox->multiVehicleManager()->vehicles();
    MAVLinkProtocol* mavlinkProtocol = _toolbox->mavlinkProtocol();
    mavlink_follow_target_t follow_target;

    memset(&follow_target, 0, sizeof(mavlink_follow_target_t));

    follow_target.timestamp = runTime.nsecsElapsed()*1e-6;
Jimmy Johnson's avatar
Jimmy Johnson committed
143
    follow_target.est_capabilities = estimatation_capabilities;
Jimmy Johnson's avatar
Jimmy Johnson committed
144 145 146 147 148
    follow_target.position_cov[0] = _motionReport.pos_std_dev[0];
    follow_target.position_cov[2] = _motionReport.pos_std_dev[2];
    follow_target.alt = _motionReport.alt;
    follow_target.lat = _motionReport.lat_int;
    follow_target.lon = _motionReport.lon_int;
Jimmy Johnson's avatar
Jimmy Johnson committed
149 150
    follow_target.vel[0] = _motionReport.vx;
    follow_target.vel[1] = _motionReport.vy;
Jimmy Johnson's avatar
Jimmy Johnson committed
151 152 153

    for (int i=0; i< vehicles.count(); i++) {
        Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]);
Jimmy Johnson's avatar
Jimmy Johnson committed
154
        if(vehicle->flightMode().compare(PX4FirmwarePlugin::followMeFlightMode, Qt::CaseInsensitive) == 0) {
Jimmy Johnson's avatar
Jimmy Johnson committed
155 156 157 158 159 160 161 162 163 164 165 166 167 168
            mavlink_message_t message;
            mavlink_msg_follow_target_encode(mavlinkProtocol->getSystemId(),
                                             mavlinkProtocol->getComponentId(),
                                             &message,
                                             &follow_target);
            vehicle->sendMessage(message);
        }
    }
}

double FollowMe::_degreesToRadian(double deg)
{
    return deg * M_PI / 180.0;
}