Commit ad6cb929 authored by Jimmy Johnson's avatar Jimmy Johnson

adding position manager

parent 37c62b78
...@@ -218,6 +218,7 @@ INCLUDEPATH += \ ...@@ -218,6 +218,7 @@ INCLUDEPATH += \
src/ViewWidgets \ src/ViewWidgets \
src/QtLocationPlugin \ src/QtLocationPlugin \
src/QtLocationPlugin/QMLControl \ src/QtLocationPlugin/QMLControl \
src/PositionManager \
FORMS += \ FORMS += \
src/ui/MainWindow.ui \ src/ui/MainWindow.ui \
...@@ -266,6 +267,7 @@ HEADERS += \ ...@@ -266,6 +267,7 @@ HEADERS += \
src/Joystick/Joystick.h \ src/Joystick/Joystick.h \
src/Joystick/JoystickManager.h \ src/Joystick/JoystickManager.h \
src/FollowMe/FollowMe.h \ src/FollowMe/FollowMe.h \
src/PositionManager/SimulatedPosition.h \
src/JsonHelper.h \ src/JsonHelper.h \
src/LogCompressor.h \ src/LogCompressor.h \
src/MG.h \ src/MG.h \
...@@ -310,6 +312,7 @@ HEADERS += \ ...@@ -310,6 +312,7 @@ HEADERS += \
src/QmlControls/QGCImageProvider.h \ src/QmlControls/QGCImageProvider.h \
src/AutoPilotPlugins/APM/APMRemoteParamsDownloader.h \ src/AutoPilotPlugins/APM/APMRemoteParamsDownloader.h \
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h \ src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h \
src/PositionManager/PositionManager.h
DebugBuild { DebugBuild {
HEADERS += \ HEADERS += \
...@@ -462,6 +465,8 @@ SOURCES += \ ...@@ -462,6 +465,8 @@ SOURCES += \
src/QmlControls/QGCImageProvider.cc \ src/QmlControls/QGCImageProvider.cc \
src/AutoPilotPlugins/APM/APMRemoteParamsDownloader.cc \ src/AutoPilotPlugins/APM/APMRemoteParamsDownloader.cc \
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc \ src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc \
src/PositionManager/SimulatedPosition.cc \
src/PositionManager/PositionManager.cpp
DebugBuild { DebugBuild {
SOURCES += \ SOURCES += \
......
...@@ -241,6 +241,7 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void) ...@@ -241,6 +241,7 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
<< MAV_CMD_DO_SET_SERVO << MAV_CMD_DO_SET_SERVO
<< MAV_CMD_DO_CHANGE_SPEED << MAV_CMD_DO_CHANGE_SPEED
<< MAV_CMD_NAV_PATHPLANNING; << MAV_CMD_NAV_PATHPLANNING;
return list; return list;
} }
......
...@@ -20,7 +20,6 @@ ...@@ -20,7 +20,6 @@
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/ ======================================================================*/
#include <QElapsedTimer> #include <QElapsedTimer>
#include <cmath> #include <cmath>
...@@ -29,47 +28,21 @@ ...@@ -29,47 +28,21 @@
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include "FollowMe.h" #include "FollowMe.h"
#include "Vehicle.h" #include "Vehicle.h"
#include "PositionManager.h"
#ifdef QT_QML_DEBUG
FollowMe::simulated_motion_s FollowMe::_simulated_motion[4] = {{0,500},{500,0},{0, -500},{-500, 0}};
#endif
FollowMe::FollowMe(QGCApplication* app) FollowMe::FollowMe(QGCApplication* app)
: QGCTool(app), : QGCTool(app), estimatation_capabilities(0)
_followMeStr(PX4FirmwarePlugin::followMeFlightMode)
{ {
#ifdef QT_QML_DEBUG
_simulate_motion_timer = 0;
_simulate_motion_index = 0;
_simulate_motion = false;
#endif
memset(&_motionReport, 0, sizeof(motionReport_s)); memset(&_motionReport, 0, sizeof(motionReport_s));
runTime.start();
// set up the QT position connection slot
_locationInfo = QGeoPositionInfoSource::createDefaultSource(this);
if(_locationInfo != 0) {
_locationInfo->setPreferredPositioningMethods(QGeoPositionInfoSource::SatellitePositioningMethods);
_locationInfo->setUpdateInterval(_locationInfo->minimumUpdateInterval());
connect(_locationInfo, SIGNAL(positionUpdated(QGeoPositionInfo)), this, SLOT(_setGPSLocation(QGeoPositionInfo)));
// set up the mavlink motion report timer`
_gcsMotionReportTimer.setInterval(_locationInfo->minimumUpdateInterval());
_gcsMotionReportTimer.setSingleShot(false); _gcsMotionReportTimer.setSingleShot(false);
connect(&_gcsMotionReportTimer, &QTimer::timeout, this, &FollowMe::_sendGCSMotionReport); connect(&_gcsMotionReportTimer, &QTimer::timeout, this, &FollowMe::_sendGCSMotionReport);
runTime.start();
}
} }
FollowMe::~FollowMe() FollowMe::~FollowMe()
{ {
disable(); _disable();
} }
void FollowMe::followMeHandleManager(const QString&) void FollowMe::followMeHandleManager(const QString&)
...@@ -78,29 +51,34 @@ void FollowMe::followMeHandleManager(const QString&) ...@@ -78,29 +51,34 @@ void FollowMe::followMeHandleManager(const QString&)
for (int i=0; i< vehicles.count(); i++) { for (int i=0; i< vehicles.count(); i++) {
Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]); Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]);
if(vehicle->flightMode().compare(_followMeStr, Qt::CaseInsensitive) == 0) { if(vehicle->flightMode().compare(PX4FirmwarePlugin::followMeFlightMode, Qt::CaseInsensitive) == 0) {
enable(); _enable();
return; return;
} }
} }
disable(); _disable();
} }
void FollowMe::enable() void FollowMe::_enable()
{ {
if(_locationInfo != 0) { connect(_toolbox->qgcPositionManager(),
_locationInfo->startUpdates(); SIGNAL(positionInfoUpdated(QGeoPositionInfo)),
this,
SLOT(_setGPSLocation(QGeoPositionInfo)));
_gcsMotionReportTimer.setInterval(_toolbox->qgcPositionManager()->updateInterval());
_gcsMotionReportTimer.start(); _gcsMotionReportTimer.start();
}
} }
void FollowMe::disable() void FollowMe::_disable()
{ {
if(_locationInfo != 0) { disconnect(_toolbox->qgcPositionManager(),
_locationInfo->stopUpdates(); SIGNAL(positionInfoUpdated(QGeoPositionInfo)),
this,
SLOT(_setGPSLocation(QGeoPositionInfo)));
_gcsMotionReportTimer.stop(); _gcsMotionReportTimer.stop();
}
} }
void FollowMe::_setGPSLocation(QGeoPositionInfo geoPositionInfo) void FollowMe::_setGPSLocation(QGeoPositionInfo geoPositionInfo)
...@@ -115,13 +93,8 @@ void FollowMe::_setGPSLocation(QGeoPositionInfo geoPositionInfo) ...@@ -115,13 +93,8 @@ void FollowMe::_setGPSLocation(QGeoPositionInfo geoPositionInfo)
_motionReport.lon_int = geoCoordinate.longitude()*1e7; _motionReport.lon_int = geoCoordinate.longitude()*1e7;
_motionReport.alt = geoCoordinate.altitude(); _motionReport.alt = geoCoordinate.altitude();
#ifdef QT_QML_DEBUG estimatation_capabilities |= (1 << POS);
if(_simulate_motion == true) {
_motionReport.lat_int = 47.3977420*1e7;
_motionReport.lon_int = 8.5455941*1e7;
_motionReport.alt = 488.00;
}
#endif
// get the current eph and epv // get the current eph and epv
if(geoPositionInfo.hasAttribute(QGeoPositionInfo::HorizontalAccuracy) == true) { if(geoPositionInfo.hasAttribute(QGeoPositionInfo::HorizontalAccuracy) == true) {
...@@ -143,11 +116,17 @@ void FollowMe::_setGPSLocation(QGeoPositionInfo geoPositionInfo) ...@@ -143,11 +116,17 @@ void FollowMe::_setGPSLocation(QGeoPositionInfo geoPositionInfo)
if((geoPositionInfo.hasAttribute(QGeoPositionInfo::Direction) == true) && if((geoPositionInfo.hasAttribute(QGeoPositionInfo::Direction) == true) &&
(geoPositionInfo.hasAttribute(QGeoPositionInfo::GroundSpeed) == true)) { (geoPositionInfo.hasAttribute(QGeoPositionInfo::GroundSpeed) == true)) {
estimatation_capabilities |= (1 << VEL);
qreal direction = _degreesToRadian(geoPositionInfo.attribute(QGeoPositionInfo::Direction)); qreal direction = _degreesToRadian(geoPositionInfo.attribute(QGeoPositionInfo::Direction));
qreal velocity = geoPositionInfo.attribute(QGeoPositionInfo::GroundSpeed); qreal velocity = geoPositionInfo.attribute(QGeoPositionInfo::GroundSpeed);
_motionReport.vx = cos(direction)*velocity; _motionReport.vx = cos(direction)*velocity;
_motionReport.vy = sin(direction)*velocity; _motionReport.vy = sin(direction)*velocity;
} else {
_motionReport.vx = 0.0f;
_motionReport.vy = 0.0f;
} }
} }
} }
...@@ -161,22 +140,20 @@ void FollowMe::_sendGCSMotionReport(void) ...@@ -161,22 +140,20 @@ void FollowMe::_sendGCSMotionReport(void)
memset(&follow_target, 0, sizeof(mavlink_follow_target_t)); memset(&follow_target, 0, sizeof(mavlink_follow_target_t));
follow_target.timestamp = runTime.nsecsElapsed()*1e-6; follow_target.timestamp = runTime.nsecsElapsed()*1e-6;
follow_target.est_capabilities = (1 << POS); follow_target.est_capabilities = estimatation_capabilities;
follow_target.position_cov[0] = _motionReport.pos_std_dev[0]; follow_target.position_cov[0] = _motionReport.pos_std_dev[0];
follow_target.position_cov[2] = _motionReport.pos_std_dev[2]; follow_target.position_cov[2] = _motionReport.pos_std_dev[2];
follow_target.alt = _motionReport.alt; follow_target.alt = _motionReport.alt;
follow_target.lat = _motionReport.lat_int; follow_target.lat = _motionReport.lat_int;
follow_target.lon = _motionReport.lon_int; follow_target.lon = _motionReport.lon_int;
follow_target.vel[0] = _motionReport.vx;
follow_target.vel[1] = _motionReport.vy;
#ifdef QT_QML_DEBUG qWarning("Mavlink Sending %d %d", _motionReport.lat_int, _motionReport.lon_int);
if(_simulate_motion == true) {
_createSimulatedMotion(follow_target);
}
#endif
for (int i=0; i< vehicles.count(); i++) { for (int i=0; i< vehicles.count(); i++) {
Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]); Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]);
if(vehicle->flightMode().compare(_followMeStr, Qt::CaseInsensitive) == 0) { if(vehicle->flightMode().compare(PX4FirmwarePlugin::followMeFlightMode, Qt::CaseInsensitive) == 0) {
mavlink_message_t message; mavlink_message_t message;
mavlink_msg_follow_target_encode(mavlinkProtocol->getSystemId(), mavlink_msg_follow_target_encode(mavlinkProtocol->getSystemId(),
mavlinkProtocol->getComponentId(), mavlinkProtocol->getComponentId(),
...@@ -191,28 +168,3 @@ double FollowMe::_degreesToRadian(double deg) ...@@ -191,28 +168,3 @@ double FollowMe::_degreesToRadian(double deg)
{ {
return deg * M_PI / 180.0; return deg * M_PI / 180.0;
} }
#ifdef QT_QML_DEBUG
void FollowMe::_createSimulatedMotion(mavlink_follow_target_t & follow_target)
{
static int f_lon = 0;
static int f_lat = 0;
static float rot = 0;
rot += (float) .1;
if(!(_simulate_motion_timer++%50)) {
_simulate_motion_index++;
if(_simulate_motion_index > 3) {
_simulate_motion_index = 0;
}
}
f_lon = f_lon + _simulated_motion[_simulate_motion_index].lon*sin(rot);
f_lat = f_lat + _simulated_motion[_simulate_motion_index].lat;
follow_target.alt = _motionReport.alt;
follow_target.lat = _motionReport.lat_int + f_lon;
follow_target.lon = _motionReport.lon_int + f_lat;
}
#endif
...@@ -30,7 +30,6 @@ ...@@ -30,7 +30,6 @@
#include <QGeoPositionInfoSource> #include <QGeoPositionInfoSource>
#include <QElapsedTimer> #include <QElapsedTimer>
#include "QGCLoggingCategory.h"
#include "QGCToolbox.h" #include "QGCToolbox.h"
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
...@@ -52,8 +51,8 @@ private slots: ...@@ -52,8 +51,8 @@ private slots:
void _sendGCSMotionReport(void); void _sendGCSMotionReport(void);
private: private:
QGeoPositionInfoSource * _locationInfo;
QElapsedTimer runTime; QElapsedTimer runTime;
QTimer _gcsMotionReportTimer; // Timer to emit motion reports
struct motionReport_s { struct motionReport_s {
uint32_t timestamp; // time since boot uint32_t timestamp; // time since boot
...@@ -69,14 +68,6 @@ private: ...@@ -69,14 +68,6 @@ private:
float pos_std_dev[3]; // -1 for unknown float pos_std_dev[3]; // -1 for unknown
} _motionReport; } _motionReport;
QString _followMeStr;
QTimer _gcsMotionReportTimer; ///< Timer to emit motion reports
double _degreesToRadian(double deg);
void disable();
void enable();
// Mavlink defined motion reporting capabilities // Mavlink defined motion reporting capabilities
enum { enum {
...@@ -86,22 +77,10 @@ private: ...@@ -86,22 +77,10 @@ private:
ATT_RATES = 3 ATT_RATES = 3
}; };
#ifdef QT_QML_DEBUG uint8_t estimatation_capabilities;
// items for simulating QGC movment in jMAVSIM
struct simulated_motion_s {
int lon;
int lat;
};
static simulated_motion_s _simulated_motion[4];
int _simulate_motion_timer; void _disable();
int _simulate_motion_index; void _enable();
bool _simulate_motion; double _degreesToRadian(double deg);
void _createSimulatedMotion(mavlink_follow_target_t & follow_target);
#endif
}; };
/*=====================================================================
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 "PositionManager.h"
QGCPositionManager::QGCPositionManager(QGCApplication* app) :
QGCTool(app),
_updateInterval(0),
_currentSource(nullptr)
{
_defaultSource = QGeoPositionInfoSource::createDefaultSource(this);
_simulatedSource = new SimulatedPosition();
// if the default source is not availble for whatever reason
// fall back to a simulated source
if(_defaultSource == nullptr) {
_defaultSource = _simulatedSource;
}
setPositionSource(QGCPositionSource::GPS);
}
QGCPositionManager::~QGCPositionManager()
{
delete(_simulatedSource);
}
void QGCPositionManager::positionUpdated(const QGeoPositionInfo &update)
{
QGeoCoordinate position(update.coordinate().latitude(), update.coordinate().longitude());
emit lastPositionUpdated(update.isValid(), QVariant::fromValue(position));
emit positionInfoUpdated(update);
}
int QGCPositionManager::updateInterval() const
{
return _updateInterval;
}
void QGCPositionManager::setPositionSource(QGCPositionManager::QGCPositionSource source)
{
if(_currentSource != nullptr) {
_currentSource->stopUpdates();
disconnect(_currentSource, SIGNAL(positionUpdated(QGeoPositionInfo)), this, SLOT(positionUpdated(QGeoPositionInfo)));
}
switch(source) {
case QGCPositionManager::Log:
break;
case QGCPositionManager::Simulated:
_currentSource = _simulatedSource;
break;
case QGCPositionManager::GPS:
default:
_currentSource = _defaultSource;
break;
}
_updateInterval = _currentSource->minimumUpdateInterval();
_currentSource->setPreferredPositioningMethods(QGeoPositionInfoSource::SatellitePositioningMethods);
_currentSource->setUpdateInterval(_updateInterval);
_currentSource->startUpdates();
connect(_currentSource, SIGNAL(positionUpdated(QGeoPositionInfo)), this, SLOT(positionUpdated(QGeoPositionInfo)));
}
/*=====================================================================
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/>.
======================================================================*/
#pragma once
#include <QtPositioning/qgeopositioninfosource.h>
#include <QVariant>
#include "QGCToolbox.h"
#include "SimulatedPosition.h"
class QGCPositionManager : public QGCTool {
Q_OBJECT
public:
QGCPositionManager(QGCApplication* app);
~QGCPositionManager();
enum QGCPositionSource {
Simulated,
GPS,
Log
};
void setPositionSource(QGCPositionSource source);
int updateInterval() const;
private slots:
void positionUpdated(const QGeoPositionInfo &update);
signals:
void lastPositionUpdated(bool valid, QVariant lastPosition);
void positionInfoUpdated(QGeoPositionInfo update);
private:
int _updateInterval;
QGeoPositionInfoSource * _currentSource;
QGeoPositionInfoSource * _defaultSource;
QGeoPositionInfoSource * _simulatedSource;
};
/*=====================================================================
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 <QtCore>
#include <QDateTime>
#include <QDate>
#include "SimulatedPosition.h"
SimulatedPosition::simulated_motion_s SimulatedPosition::_simulated_motion[5] = {{0,250},{0,0},{0, -250},{-250, 0},{0,0}};
SimulatedPosition::SimulatedPosition()
: QGeoPositionInfoSource(NULL),
lat_int(47.3977420*1e7),
lon_int(8.5455941*1e7),
_step_cnt(0),
_simulate_motion_index(0),
_simulate_motion(true),
_rotation(0.0F)
{
QDateTime currentDateTime = QDateTime::currentDateTime();
qsrand(currentDateTime.toTime_t());
connect(&update_timer, &QTimer::timeout, this, &SimulatedPosition::updatePosition);
}
QGeoPositionInfo SimulatedPosition::lastKnownPosition(bool /*fromSatellitePositioningMethodsOnly*/) const
{
return lastPosition;
}
SimulatedPosition::PositioningMethods SimulatedPosition::supportedPositioningMethods() const
{
return AllPositioningMethods;
}
int SimulatedPosition::minimumUpdateInterval() const
{
return 1000;
}
void SimulatedPosition::startUpdates()
{
int interval = updateInterval();
if (interval < minimumUpdateInterval())
interval = minimumUpdateInterval();
update_timer.setSingleShot(false);
update_timer.start(interval);
}
void SimulatedPosition::stopUpdates()
{
update_timer.stop();
}
void SimulatedPosition::requestUpdate(int /*timeout*/)
{
emit updateTimeout();
}
int SimulatedPosition::getRandomNumber(int size)
{
if(size == 0) {
return 0;
}
int num = (qrand()%2 > 1) ? -1 : 1;
return num*qrand()%size;
}
void SimulatedPosition::updatePosition()
{
int32_t lat_mov = 0;
int32_t lon_mov = 0;
_rotation += (float) .1;
if(!(_step_cnt++%30)) {
_simulate_motion_index++;
if(_simulate_motion_index > 4) {
_simulate_motion_index = 0;
}
}
lat_mov = _simulated_motion[_simulate_motion_index].lat;
lon_mov = _simulated_motion[_simulate_motion_index].lon*sin(_rotation);
lon_int += lat_mov;
lat_int += lon_mov;
double latitude = ((double) (lat_int + getRandomNumber(250)))*1e-7;
double longitude = ((double) (lon_int + getRandomNumber(250)))*1e-7;
QDateTime timestamp = QDateTime::currentDateTime();
QGeoCoordinate position(latitude, longitude);
QGeoPositionInfo info(position, timestamp);
if(lat_mov || lon_mov) {
info.setAttribute(QGeoPositionInfo::Attribute::Direction, 3.14/2);
info.setAttribute(QGeoPositionInfo::Attribute::GroundSpeed, 5);
}
lastPosition = info;
emit positionUpdated(info);
}
QGeoPositionInfoSource::Error SimulatedPosition::error() const
{
return QGeoPositionInfoSource::NoError;
}
/*=====================================================================
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/>.
======================================================================*/
#pragma once
#include <QtPositioning/qgeopositioninfosource.h>
#include "QGCToolbox.h"
#include <QTimer>
class SimulatedPosition : public QGeoPositionInfoSource
{
Q_OBJECT
public:
SimulatedPosition();
QGeoPositionInfo lastKnownPosition(bool fromSatellitePositioningMethodsOnly = false) const;
PositioningMethods supportedPositioningMethods() const;
int minimumUpdateInterval() const;
Error error() const;
public slots:
virtual void startUpdates();
virtual void stopUpdates();
virtual void requestUpdate(int timeout = 5000);
private slots:
void updatePosition();
private:
QTimer update_timer;
QGeoPositionInfo lastPosition;
// items for simulating QGC movment in jMAVSIM
int32_t lat_int;
int32_t lon_int;
struct simulated_motion_s {
int lon;
int lat;
};
static simulated_motion_s _simulated_motion[5];
int getRandomNumber(int size);
int _step_cnt;
int _simulate_motion_index;
bool _simulate_motion;
float _rotation;
};
...@@ -103,6 +103,9 @@ ...@@ -103,6 +103,9 @@
#include "PX4AirframeLoader.h" #include "PX4AirframeLoader.h"
#include "ValuesWidgetController.h" #include "ValuesWidgetController.h"
#include "AppMessages.h" #include "AppMessages.h"
#include "SimulatedPosition.h"
#include "PositionManager.h"
#include "FollowMe.h"
#ifndef __ios__ #ifndef __ios__
#include "SerialLink.h" #include "SerialLink.h"
...@@ -440,6 +443,7 @@ void QGCApplication::_initCommon(void) ...@@ -440,6 +443,7 @@ void QGCApplication::_initCommon(void)
qmlRegisterUncreatableType<MissionManager> ("QGroundControl.Vehicle", 1, 0, "MissionManager", "Reference only"); qmlRegisterUncreatableType<MissionManager> ("QGroundControl.Vehicle", 1, 0, "MissionManager", "Reference only");
qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only"); qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only");
qmlRegisterUncreatableType<Joystick> ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only"); qmlRegisterUncreatableType<Joystick> ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only");
qmlRegisterUncreatableType<QGCPositionManager> ("QGroundControl.QGCPositionManager", 1, 0, "QGCPositionManager", "Reference only");
qmlRegisterType<ParameterEditorController> ("QGroundControl.Controllers", 1, 0, "ParameterEditorController"); qmlRegisterType<ParameterEditorController> ("QGroundControl.Controllers", 1, 0, "ParameterEditorController");
qmlRegisterType<APMFlightModesComponentController> ("QGroundControl.Controllers", 1, 0, "APMFlightModesComponentController"); qmlRegisterType<APMFlightModesComponentController> ("QGroundControl.Controllers", 1, 0, "APMFlightModesComponentController");
......
...@@ -39,6 +39,7 @@ ...@@ -39,6 +39,7 @@
#include "UASMessageHandler.h" #include "UASMessageHandler.h"
#include "QGCMapEngineManager.h" #include "QGCMapEngineManager.h"
#include "FollowMe.h" #include "FollowMe.h"
#include "PositionManager.h"
QGCToolbox::QGCToolbox(QGCApplication* app) QGCToolbox::QGCToolbox(QGCApplication* app)
: _audioOutput(NULL) : _audioOutput(NULL)
...@@ -56,6 +57,7 @@ QGCToolbox::QGCToolbox(QGCApplication* app) ...@@ -56,6 +57,7 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
, _mapEngineManager(NULL) , _mapEngineManager(NULL)
, _uasMessageHandler(NULL) , _uasMessageHandler(NULL)
, _followMe(NULL) , _followMe(NULL)
, _qgcPositionManager(NULL)
{ {
_audioOutput = new GAudioOutput(app); _audioOutput = new GAudioOutput(app);
_autopilotPluginManager = new AutoPilotPluginManager(app); _autopilotPluginManager = new AutoPilotPluginManager(app);
...@@ -74,6 +76,7 @@ QGCToolbox::QGCToolbox(QGCApplication* app) ...@@ -74,6 +76,7 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
_multiVehicleManager = new MultiVehicleManager(app); _multiVehicleManager = new MultiVehicleManager(app);
_mapEngineManager = new QGCMapEngineManager(app); _mapEngineManager = new QGCMapEngineManager(app);
_uasMessageHandler = new UASMessageHandler(app); _uasMessageHandler = new UASMessageHandler(app);
_qgcPositionManager = new QGCPositionManager(app);
_followMe = new FollowMe(app); _followMe = new FollowMe(app);
_audioOutput->setToolbox(this); _audioOutput->setToolbox(this);
...@@ -94,9 +97,9 @@ QGCToolbox::QGCToolbox(QGCApplication* app) ...@@ -94,9 +97,9 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
_mapEngineManager->setToolbox(this); _mapEngineManager->setToolbox(this);
_uasMessageHandler->setToolbox(this); _uasMessageHandler->setToolbox(this);
_followMe->setToolbox(this); _followMe->setToolbox(this);
//FIXME: make this configurable... //FIXME: make this configurable...
//_gpsManager->setupGPS("ttyACM0"); //_gpsManager->setupGPS("ttyACM0");
_qgcPositionManager->setToolbox(this);
} }
QGCToolbox::~QGCToolbox() QGCToolbox::~QGCToolbox()
...@@ -115,6 +118,7 @@ QGCToolbox::~QGCToolbox() ...@@ -115,6 +118,7 @@ QGCToolbox::~QGCToolbox()
delete _multiVehicleManager; delete _multiVehicleManager;
delete _uasMessageHandler; delete _uasMessageHandler;
delete _followMe; delete _followMe;
delete _qgcPositionManager;
} }
QGCTool::QGCTool(QGCApplication* app) QGCTool::QGCTool(QGCApplication* app)
......
...@@ -43,6 +43,7 @@ class QGCMapEngineManager; ...@@ -43,6 +43,7 @@ class QGCMapEngineManager;
class QGCApplication; class QGCApplication;
class QGCImageProvider; class QGCImageProvider;
class UASMessageHandler; class UASMessageHandler;
class QGCPositionManager;
/// This is used to manage all of our top level services/tools /// This is used to manage all of our top level services/tools
class QGCToolbox { class QGCToolbox {
...@@ -65,6 +66,7 @@ public: ...@@ -65,6 +66,7 @@ public:
QGCImageProvider* imageProvider() { return _imageProvider; } QGCImageProvider* imageProvider() { return _imageProvider; }
UASMessageHandler* uasMessageHandler(void) { return _uasMessageHandler; } UASMessageHandler* uasMessageHandler(void) { return _uasMessageHandler; }
FollowMe* followMe(void) { return _followMe; } FollowMe* followMe(void) { return _followMe; }
QGCPositionManager* qgcPositionManager(void) { return _qgcPositionManager; }
private: private:
GAudioOutput* _audioOutput; GAudioOutput* _audioOutput;
...@@ -83,6 +85,7 @@ private: ...@@ -83,6 +85,7 @@ private:
QGCMapEngineManager* _mapEngineManager; QGCMapEngineManager* _mapEngineManager;
UASMessageHandler* _uasMessageHandler; UASMessageHandler* _uasMessageHandler;
FollowMe* _followMe; FollowMe* _followMe;
QGCPositionManager* _qgcPositionManager;
}; };
/// This is the base class for all tools /// This is the base class for all tools
......
...@@ -71,6 +71,7 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox) ...@@ -71,6 +71,7 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
_missionCommands = toolbox->missionCommands(); _missionCommands = toolbox->missionCommands();
_multiVehicleManager = toolbox->multiVehicleManager(); _multiVehicleManager = toolbox->multiVehicleManager();
_mapEngineManager = toolbox->mapEngineManager(); _mapEngineManager = toolbox->mapEngineManager();
_qgcPositionManager = toolbox->qgcPositionManager();
} }
......
...@@ -35,6 +35,7 @@ ...@@ -35,6 +35,7 @@
#include "MissionCommands.h" #include "MissionCommands.h"
#include "SettingsFact.h" #include "SettingsFact.h"
#include "FactMetaData.h" #include "FactMetaData.h"
#include "SimulatedPosition.h"
#ifdef QT_DEBUG #ifdef QT_DEBUG
#include "MockLink.h" #include "MockLink.h"
...@@ -72,6 +73,7 @@ public: ...@@ -72,6 +73,7 @@ public:
Q_PROPERTY(MissionCommands* missionCommands READ missionCommands CONSTANT) Q_PROPERTY(MissionCommands* missionCommands READ missionCommands CONSTANT)
Q_PROPERTY(MultiVehicleManager* multiVehicleManager READ multiVehicleManager CONSTANT) Q_PROPERTY(MultiVehicleManager* multiVehicleManager READ multiVehicleManager CONSTANT)
Q_PROPERTY(QGCMapEngineManager* mapEngineManager READ mapEngineManager CONSTANT) Q_PROPERTY(QGCMapEngineManager* mapEngineManager READ mapEngineManager CONSTANT)
Q_PROPERTY(QGCPositionManager* qgcPositionManger READ qgcPositionManger CONSTANT)
Q_PROPERTY(qreal zOrderTopMost READ zOrderTopMost CONSTANT) ///< z order for top most items, toolbar, main window sub view Q_PROPERTY(qreal zOrderTopMost READ zOrderTopMost CONSTANT) ///< z order for top most items, toolbar, main window sub view
Q_PROPERTY(qreal zOrderWidgets READ zOrderWidgets CONSTANT) ///< z order value to widgets, for example: zoom controls, hud widgetss Q_PROPERTY(qreal zOrderWidgets READ zOrderWidgets CONSTANT) ///< z order value to widgets, for example: zoom controls, hud widgetss
...@@ -138,6 +140,7 @@ public: ...@@ -138,6 +140,7 @@ public:
MissionCommands* missionCommands () { return _missionCommands; } MissionCommands* missionCommands () { return _missionCommands; }
MultiVehicleManager* multiVehicleManager () { return _multiVehicleManager; } MultiVehicleManager* multiVehicleManager () { return _multiVehicleManager; }
QGCMapEngineManager* mapEngineManager () { return _mapEngineManager; } QGCMapEngineManager* mapEngineManager () { return _mapEngineManager; }
QGCPositionManager* qgcPositionManger () { return _qgcPositionManager; }
qreal zOrderTopMost () { return 1000; } qreal zOrderTopMost () { return 1000; }
qreal zOrderWidgets () { return 100; } qreal zOrderWidgets () { return 100; }
...@@ -202,6 +205,7 @@ private: ...@@ -202,6 +205,7 @@ private:
MissionCommands* _missionCommands; MissionCommands* _missionCommands;
MultiVehicleManager* _multiVehicleManager; MultiVehicleManager* _multiVehicleManager;
QGCMapEngineManager* _mapEngineManager; QGCMapEngineManager* _mapEngineManager;
QGCPositionManager* _qgcPositionManager;
bool _virtualTabletJoystick; bool _virtualTabletJoystick;
......
...@@ -32,6 +32,7 @@ import QGroundControl.Controls 1.0 ...@@ -32,6 +32,7 @@ import QGroundControl.Controls 1.0
import QGroundControl.FlightDisplay 1.0 import QGroundControl.FlightDisplay 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.MultiVehicleManager 1.0 import QGroundControl.MultiVehicleManager 1.0
import QGroundControl.QGCPositionManager 1.0
/// Inner common QML for mainWindow /// Inner common QML for mainWindow
Item { Item {
...@@ -176,18 +177,16 @@ Item { ...@@ -176,18 +177,16 @@ Item {
//-- Detect tablet position //-- Detect tablet position
PositionSource { Connections {
id: positionSource target: QGroundControl.qgcPositionManger
updateInterval: 1000
active: true onLastPositionUpdated: {
if(valid) {
onPositionChanged: { if(lastPosition.latitude) {
if(positionSource.valid) { if(Math.abs(lastPosition.latitude) > 0.001) {
if(positionSource.position.coordinate.latitude) { if(lastPosition.longitude) {
if(Math.abs(positionSource.position.coordinate.latitude) > 0.001) { if(Math.abs(lastPosition.longitude) > 0.001) {
if(positionSource.position.coordinate.longitude) { gcsPosition = QtPositioning.coordinate(lastPosition.latitude,lastPosition.longitude)
if(Math.abs(positionSource.position.coordinate.longitude) > 0.001) {
gcsPosition = positionSource.position.coordinate
} }
} }
} }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment