FollowMe.cc 5.3 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
Jimmy Johnson's avatar
Jimmy Johnson committed
9 10 11 12 13

#include <QElapsedTimer>
#include <cmath>

#include "MultiVehicleManager.h"
14
#include "FirmwarePlugin.h"
Jimmy Johnson's avatar
Jimmy Johnson committed
15 16 17
#include "MAVLinkProtocol.h"
#include "FollowMe.h"
#include "Vehicle.h"
Jimmy Johnson's avatar
Jimmy Johnson committed
18
#include "PositionManager.h"
Jimmy Johnson's avatar
Jimmy Johnson committed
19

20 21
FollowMe::FollowMe(QGCApplication* app, QGCToolbox* toolbox)
    : QGCTool(app, toolbox), estimatation_capabilities(0)
Jimmy Johnson's avatar
Jimmy Johnson committed
22 23
{
    memset(&_motionReport, 0, sizeof(motionReport_s));
Jimmy Johnson's avatar
Jimmy Johnson committed
24
    runTime.start();
Jimmy Johnson's avatar
Jimmy Johnson committed
25

Jimmy Johnson's avatar
Jimmy Johnson committed
26 27
    _gcsMotionReportTimer.setSingleShot(false);
    connect(&_gcsMotionReportTimer, &QTimer::timeout, this, &FollowMe::_sendGCSMotionReport);
Jimmy Johnson's avatar
Jimmy Johnson committed
28 29 30 31 32 33 34 35
}

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]);
36
        if (vehicle->px4Firmware() && vehicle->flightMode().compare(FirmwarePlugin::px4FollowMeFlightMode, Qt::CaseInsensitive) == 0) {
Jimmy Johnson's avatar
Jimmy Johnson committed
37
            _enable();
Jimmy Johnson's avatar
Jimmy Johnson committed
38 39 40 41
            return;
        }
    }

Jimmy Johnson's avatar
Jimmy Johnson committed
42
    _disable();
Jimmy Johnson's avatar
Jimmy Johnson committed
43 44
}

Jimmy Johnson's avatar
Jimmy Johnson committed
45
void FollowMe::_enable()
Jimmy Johnson's avatar
Jimmy Johnson committed
46
{
Jimmy Johnson's avatar
Jimmy Johnson committed
47 48 49 50 51 52 53
    connect(_toolbox->qgcPositionManager(),
            SIGNAL(positionInfoUpdated(QGeoPositionInfo)),
            this,
            SLOT(_setGPSLocation(QGeoPositionInfo)));

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

Jimmy Johnson's avatar
Jimmy Johnson committed
56
void FollowMe::_disable()
Jimmy Johnson's avatar
Jimmy Johnson committed
57
{
Jimmy Johnson's avatar
Jimmy Johnson committed
58 59 60 61 62 63
    disconnect(_toolbox->qgcPositionManager(),
               SIGNAL(positionInfoUpdated(QGeoPositionInfo)),
               this,
               SLOT(_setGPSLocation(QGeoPositionInfo)));

    _gcsMotionReportTimer.stop();
Jimmy Johnson's avatar
Jimmy Johnson committed
64 65 66 67 68 69 70 71 72 73 74 75 76 77
}

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
78 79
        estimatation_capabilities |= (1 << POS);

Jimmy Johnson's avatar
Jimmy Johnson committed
80 81 82 83 84 85 86 87
        // 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
88
        }                
Jimmy Johnson's avatar
Jimmy Johnson committed
89

Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
90
        // calculate z velocity if it's available
Jimmy Johnson's avatar
Jimmy Johnson committed
91 92 93 94 95

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

Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
96
        // calculate x,y velocity if it's available
Jimmy Johnson's avatar
Jimmy Johnson committed
97 98 99 100

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

Jimmy Johnson's avatar
Jimmy Johnson committed
101 102
            estimatation_capabilities |= (1 << VEL);

Jimmy Johnson's avatar
Jimmy Johnson committed
103 104 105 106 107
            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
108 109 110 111

        } else {
            _motionReport.vx = 0.0f;
            _motionReport.vy = 0.0f;
Jimmy Johnson's avatar
Jimmy Johnson committed
112 113 114 115 116 117 118 119 120 121
        }
    }
}

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

Don Gagne's avatar
Don Gagne committed
122
    memset(&follow_target, 0, sizeof(follow_target));
Jimmy Johnson's avatar
Jimmy Johnson committed
123 124

    follow_target.timestamp = runTime.nsecsElapsed()*1e-6;
Jimmy Johnson's avatar
Jimmy Johnson committed
125
    follow_target.est_capabilities = estimatation_capabilities;
Jimmy Johnson's avatar
Jimmy Johnson committed
126 127 128 129 130
    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
131 132
    follow_target.vel[0] = _motionReport.vx;
    follow_target.vel[1] = _motionReport.vy;
Jimmy Johnson's avatar
Jimmy Johnson committed
133 134 135

    for (int i=0; i< vehicles.count(); i++) {
        Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]);
136
        if(vehicle->flightMode().compare(FirmwarePlugin::px4FollowMeFlightMode, Qt::CaseInsensitive) == 0) {
Jimmy Johnson's avatar
Jimmy Johnson committed
137
            mavlink_message_t message;
138 139 140 141 142 143
            mavlink_msg_follow_target_encode_chan(mavlinkProtocol->getSystemId(),
                                                  mavlinkProtocol->getComponentId(),
                                                  vehicle->priorityLink()->mavlinkChannel(),
                                                  &message,
                                                  &follow_target);
            vehicle->sendMessageOnLink(vehicle->priorityLink(), message);
Jimmy Johnson's avatar
Jimmy Johnson committed
144 145 146 147 148 149 150 151
        }
    }
}

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