Newer
Older
/*=====================================================================
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"
_gcsMotionReportTimer.setSingleShot(false);
connect(&_gcsMotionReportTimer, &QTimer::timeout, this, &FollowMe::_sendGCSMotionReport);
}
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]);
if(vehicle->flightMode().compare(PX4FirmwarePlugin::followMeFlightMode, Qt::CaseInsensitive) == 0) {
_enable();
connect(_toolbox->qgcPositionManager(),
SIGNAL(positionInfoUpdated(QGeoPositionInfo)),
this,
SLOT(_setGPSLocation(QGeoPositionInfo)));
_gcsMotionReportTimer.setInterval(_toolbox->qgcPositionManager()->updateInterval());
_gcsMotionReportTimer.start();
disconnect(_toolbox->qgcPositionManager(),
SIGNAL(positionInfoUpdated(QGeoPositionInfo)),
this,
SLOT(_setGPSLocation(QGeoPositionInfo)));
_gcsMotionReportTimer.stop();
}
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();
// 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);
// 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)) {
qreal direction = _degreesToRadian(geoPositionInfo.attribute(QGeoPositionInfo::Direction));
qreal velocity = geoPositionInfo.attribute(QGeoPositionInfo::GroundSpeed);
_motionReport.vx = cos(direction)*velocity;
_motionReport.vy = sin(direction)*velocity;
} else {
_motionReport.vx = 0.0f;
_motionReport.vy = 0.0f;
}
}
}
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;
follow_target.est_capabilities = estimatation_capabilities;
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;
follow_target.vel[0] = _motionReport.vx;
follow_target.vel[1] = _motionReport.vy;
qWarning("Mavlink Sending %d %d", _motionReport.lat_int, _motionReport.lon_int);
for (int i=0; i< vehicles.count(); i++) {
Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]);
if(vehicle->flightMode().compare(PX4FirmwarePlugin::followMeFlightMode, Qt::CaseInsensitive) == 0) {
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;
}