Newer
Older
/****************************************************************************
*
* (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.
*
****************************************************************************/
#include <QElapsedTimer>
#include <cmath>
#include "MultiVehicleManager.h"
#include "MAVLinkProtocol.h"
#include "FollowMe.h"
#include "Vehicle.h"
#include "SettingsManager.h"
#include "AppSettings.h"
FollowMe::FollowMe(QGCApplication* app, QGCToolbox* toolbox)
}
void FollowMe::setToolbox(QGCToolbox* toolbox)
{
QGCTool::setToolbox(toolbox);
connect(&_gcsMotionReportTimer, &QTimer::timeout, this, &FollowMe::_sendGCSMotionReport);
connect(toolbox->settingsManager()->appSettings()->followTarget(), &Fact::rawValueChanged, this, &FollowMe::_settingsChanged);
_settingsChanged();
_currentMode = _toolbox->settingsManager()->appSettings()->followTarget()->rawValue().toUInt();
switch (_currentMode) {
case MODE_NEVER:
disconnect(_toolbox->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded);
disconnect(_toolbox->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved);
_disableFollowSend();
break;
case MODE_ALWAYS:
connect(_toolbox->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded);
connect(_toolbox->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved);
_enableFollowSend();
break;
case MODE_FOLLOWME:
connect(_toolbox->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded);
connect(_toolbox->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved);
_enableIfVehicleInFollow();
break;
if (!_gcsMotionReportTimer.isActive()) {
_gcsMotionReportTimer.setInterval(qMax(_toolbox->qgcPositionManager()->updateInterval(), 250));
_gcsMotionReportTimer.start();
}
if (_gcsMotionReportTimer.isActive()) {
_gcsMotionReportTimer.stop();
}
QGeoPositionInfo geoPositionInfo = _toolbox->qgcPositionManager()->geoPositionInfo();
QGeoCoordinate gcsCoordinate = geoPositionInfo.coordinate();
motionReport.lat_int = static_cast<int>(gcsCoordinate.latitude() * 1e7);
motionReport.lon_int = static_cast<int>(gcsCoordinate.longitude() * 1e7);
motionReport.altMetersAMSL = gcsCoordinate.altitude();
estimatation_capabilities |= (1 << POS);
if (geoPositionInfo.hasAttribute(QGeoPositionInfo::Direction) == true) {
motionReport.headingDegrees = geoPositionInfo.attribute(QGeoPositionInfo::Direction);
}
if (geoPositionInfo.hasAttribute(QGeoPositionInfo::HorizontalAccuracy)) {
motionReport.pos_std_dev[0] = motionReport.pos_std_dev[1] = geoPositionInfo.attribute(QGeoPositionInfo::HorizontalAccuracy);
}
if (geoPositionInfo.hasAttribute(QGeoPositionInfo::VerticalAccuracy)) {
motionReport.pos_std_dev[2] = geoPositionInfo.attribute(QGeoPositionInfo::VerticalAccuracy);
}
// calculate z velocity if it's available
if (geoPositionInfo.hasAttribute(QGeoPositionInfo::VerticalSpeed)) {
motionReport.vzMetersPerSec = geoPositionInfo.attribute(QGeoPositionInfo::VerticalSpeed);
}
if (geoPositionInfo.hasAttribute(QGeoPositionInfo::Direction) && geoPositionInfo.hasAttribute(QGeoPositionInfo::GroundSpeed) == true) {
estimatation_capabilities |= (1 << VEL);
qreal direction = _degreesToRadian(geoPositionInfo.attribute(QGeoPositionInfo::Direction));
qreal velocity = geoPositionInfo.attribute(QGeoPositionInfo::GroundSpeed);
motionReport.vxMetersPerSec = cos(direction)*velocity;
motionReport.vyMetersPerSec = sin(direction)*velocity;
} else {
motionReport.vxMetersPerSec = 0;
motionReport.vyMetersPerSec = 0;
}
for (int i=0; i<vehicles->count(); i++) {
Vehicle* vehicle = vehicles->value<Vehicle*>(i);
if (_currentMode == MODE_ALWAYS || (_currentMode == MODE_FOLLOWME && _isFollowFlightMode(vehicle, vehicle->flightMode()))) {
vehicle->firmwarePlugin()->sendGCSMotionReport(vehicle, motionReport, estimatation_capabilities);
double FollowMe::_degreesToRadian(double deg)
{
return deg * M_PI / 180.0;
}
void FollowMe::_vehicleAdded(Vehicle* vehicle)
connect(vehicle, &Vehicle::flightModeChanged, this, &FollowMe::_enableIfVehicleInFollow);
_enableIfVehicleInFollow();
}
void FollowMe::_vehicleRemoved(Vehicle* vehicle)
{
disconnect(vehicle, &Vehicle::flightModeChanged, this, &FollowMe::_enableIfVehicleInFollow);
_enableIfVehicleInFollow();
}
void FollowMe::_enableIfVehicleInFollow(void)
{
if (_currentMode == MODE_ALWAYS) {
// System always enabled
// Any vehicle in follow mode will enable the system
QmlObjectListModel* vehicles = _toolbox->multiVehicleManager()->vehicles();
for (int i=0; i< vehicles->count(); i++) {
Vehicle* vehicle = vehicles->value<Vehicle*>(i);
if (_isFollowFlightMode(vehicle, vehicle->flightMode())) {
_enableFollowSend();
return;
bool FollowMe::_isFollowFlightMode (Vehicle* vehicle, const QString& flightMode)