Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
e79dd41d
Commit
e79dd41d
authored
Aug 29, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
UASManager -> HomePositionManager
parent
f10e77cb
Changes
21
Hide whitespace changes
Inline
Side-by-side
Showing
21 changed files
with
85 additions
and
279 deletions
+85
-279
QGCApplication.pro
QGCApplication.pro
+2
-3
HomePositionManager.cc
src/HomePositionManager.cc
+37
-79
HomePositionManager.h
src/HomePositionManager.h
+12
-63
QGCApplication.cc
src/QGCApplication.cc
+6
-6
QGCSingleton.h
src/QGCSingleton.h
+1
-3
SetupView.cc
src/VehicleSetup/SetupView.cc
+0
-1
SetupViewTest.cc
src/VehicleSetup/SetupViewTest.cc
+0
-1
CustomCommandWidgetController.h
src/ViewWidgets/CustomCommandWidgetController.h
+0
-1
ViewWidgetController.cc
src/ViewWidgets/ViewWidgetController.cc
+0
-1
ViewWidgetController.h
src/ViewWidgets/ViewWidgetController.h
+0
-1
QGCFlightGearLink.cc
src/comm/QGCFlightGearLink.cc
+4
-3
QGCXPlaneLink.cc
src/comm/QGCXPlaneLink.cc
+1
-0
UAS.cc
src/uas/UAS.cc
+5
-5
UASManagerInterface.h
src/uas/UASManagerInterface.h
+0
-89
UASWaypointManager.cc
src/uas/UASWaypointManager.cc
+2
-2
HSIDisplay.cc
src/ui/HSIDisplay.cc
+2
-7
MAVLinkDecoder.cc
src/ui/MAVLinkDecoder.cc
+0
-1
MainWindow.cc
src/ui/MainWindow.cc
+2
-1
MainWindow.h
src/ui/MainWindow.h
+0
-1
WaypointList.cc
src/ui/WaypointList.cc
+7
-7
QGCMapWidget.cc
src/ui/map/QGCMapWidget.cc
+4
-4
No files found.
QGCApplication.pro
View file @
e79dd41d
...
...
@@ -240,6 +240,7 @@ HEADERS += \
src
/
comm
/
TCPLink
.
h
\
src
/
comm
/
UDPLink
.
h
\
src
/
GAudioOutput
.
h
\
src
/
HomePositionManager
.
h
\
src
/
LogCompressor
.
h
\
src
/
MG
.
h
\
src
/
QGC
.
h
\
...
...
@@ -263,8 +264,6 @@ HEADERS += \
src
/
uas
/
FileManager
.
h
\
src
/
uas
/
UAS
.
h
\
src
/
uas
/
UASInterface
.
h
\
src
/
uas
/
UASManager
.
h
\
src
/
uas
/
UASManagerInterface
.
h
\
src
/
uas
/
UASMessageHandler
.
h
\
src
/
uas
/
UASWaypointManager
.
h
\
src
/
ui
/
flightdisplay
/
FlightDisplay
.
h
\
...
...
@@ -377,6 +376,7 @@ SOURCES += \
src
/
comm
/
TCPLink
.
cc
\
src
/
comm
/
UDPLink
.
cc
\
src
/
GAudioOutput
.
cc
\
src
/
HomePositionManager
.
cc
\
src
/
LogCompressor
.
cc
\
src
/
main
.
cc
\
src
/
QGC
.
cc
\
...
...
@@ -395,7 +395,6 @@ SOURCES += \
src
/
QmlControls
/
ScreenToolsController
.
cc
\
src
/
uas
/
FileManager
.
cc
\
src
/
uas
/
UAS
.
cc
\
src
/
uas
/
UASManager
.
cc
\
src
/
uas
/
UASMessageHandler
.
cc
\
src
/
uas
/
UASWaypointManager
.
cc
\
src
/
ui
/
flightdisplay
/
FlightDisplay
.
cc
\
...
...
src/
uas/UAS
Manager.cc
→
src/
HomePosition
Manager.cc
View file @
e79dd41d
/*==================================================================
======================================================================*/
/**
* @file
* @brief Implementation of class UASManager
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2015 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 <QList>
#include <QApplication>
...
...
@@ -15,7 +28,7 @@
#include "UAS.h"
#include "UASInterface.h"
#include "
UAS
Manager.h"
#include "
HomePosition
Manager.h"
#include "QGC.h"
#include "QGCMessageBox.h"
#include "QGCApplication.h"
...
...
@@ -25,26 +38,24 @@
#define MEAN_EARTH_DIAMETER 12756274.0
#define UMR 0.017453292519943295769236907684886
IMPLEMENT_QGC_SINGLETON
(
UASManager
,
UASManagerInterface
)
IMPLEMENT_QGC_SINGLETON
(
HomePositionManager
,
HomePositionManager
)
UASManager
::
UASManager
(
QObject
*
parent
)
:
UASManagerInterface
(
parent
),
offlineUASWaypointManager
(
NULL
),
HomePositionManager
::
HomePositionManager
(
QObject
*
parent
)
:
QObject
(
parent
),
homeLat
(
47.3769
),
homeLon
(
8.549444
),
homeAlt
(
470.0
),
homeFrame
(
MAV_FRAME_GLOBAL
)
{
loadSettings
();
setLocalNEDSafetyBorders
(
1
,
-
1
,
0
,
-
1
,
1
,
-
1
);
}
UASManager
::~
UAS
Manager
()
HomePositionManager
::~
HomePosition
Manager
()
{
storeSettings
();
}
void
UAS
Manager
::
storeSettings
()
void
HomePosition
Manager
::
storeSettings
()
{
QSettings
settings
;
settings
.
beginGroup
(
"QGC_UASMANAGER"
);
...
...
@@ -54,7 +65,7 @@ void UASManager::storeSettings()
settings
.
endGroup
();
}
void
UAS
Manager
::
loadSettings
()
void
HomePosition
Manager
::
loadSettings
()
{
QSettings
settings
;
settings
.
beginGroup
(
"QGC_UASMANAGER"
);
...
...
@@ -72,7 +83,7 @@ void UASManager::loadSettings()
settings
.
endGroup
();
}
bool
UAS
Manager
::
setHomePosition
(
double
lat
,
double
lon
,
double
alt
)
bool
HomePosition
Manager
::
setHomePosition
(
double
lat
,
double
lon
,
double
alt
)
{
// Checking for NaN and infitiny
// and checking for borders
...
...
@@ -101,7 +112,7 @@ bool UASManager::setHomePosition(double lat, double lon, double alt)
return
changed
;
}
bool
UAS
Manager
::
setHomePositionAndNotify
(
double
lat
,
double
lon
,
double
alt
)
bool
HomePosition
Manager
::
setHomePositionAndNotify
(
double
lat
,
double
lon
,
double
alt
)
{
// Checking for NaN and infitiny
// and checking for borders
...
...
@@ -114,28 +125,7 @@ bool UASManager::setHomePositionAndNotify(double lat, double lon, double alt)
return
changed
;
}
/**
* @param x1 Point 1 coordinate in x dimension
* @param y1 Point 1 coordinate in y dimension
* @param z1 Point 1 coordinate in z dimension
*
* @param x2 Point 2 coordinate in x dimension
* @param y2 Point 2 coordinate in y dimension
* @param z2 Point 2 coordinate in z dimension
*/
void
UASManager
::
setLocalNEDSafetyBorders
(
double
x1
,
double
y1
,
double
z1
,
double
x2
,
double
y2
,
double
z2
)
{
nedSafetyLimitPosition1
.
x
()
=
x1
;
nedSafetyLimitPosition1
.
y
()
=
y1
;
nedSafetyLimitPosition1
.
z
()
=
z1
;
nedSafetyLimitPosition2
.
x
()
=
x2
;
nedSafetyLimitPosition2
.
y
()
=
y2
;
nedSafetyLimitPosition2
.
z
()
=
z2
;
}
void
UASManager
::
initReference
(
const
double
&
latitude
,
const
double
&
longitude
,
const
double
&
altitude
)
void
HomePositionManager
::
initReference
(
const
double
&
latitude
,
const
double
&
longitude
,
const
double
&
altitude
)
{
Eigen
::
Matrix3d
R
;
double
s_long
,
s_lat
,
c_long
,
c_lat
;
...
...
@@ -159,7 +149,7 @@ void UASManager::initReference(const double & latitude, const double & longitude
ecef_ref_point_
=
wgs84ToEcef
(
latitude
,
longitude
,
altitude
);
}
Eigen
::
Vector3d
UAS
Manager
::
wgs84ToEcef
(
const
double
&
latitude
,
const
double
&
longitude
,
const
double
&
altitude
)
Eigen
::
Vector3d
HomePosition
Manager
::
wgs84ToEcef
(
const
double
&
latitude
,
const
double
&
longitude
,
const
double
&
altitude
)
{
const
double
a
=
6378137.0
;
// semi-major axis
const
double
e_sq
=
6.69437999014e-3
;
// first eccentricity squared
...
...
@@ -179,12 +169,12 @@ Eigen::Vector3d UASManager::wgs84ToEcef(const double & latitude, const double &
return
ecef
;
}
Eigen
::
Vector3d
UAS
Manager
::
ecefToEnu
(
const
Eigen
::
Vector3d
&
ecef
)
Eigen
::
Vector3d
HomePosition
Manager
::
ecefToEnu
(
const
Eigen
::
Vector3d
&
ecef
)
{
return
ecef_ref_orientation_
*
(
ecef
-
ecef_ref_point_
);
}
void
UAS
Manager
::
wgs84ToEnu
(
const
double
&
lat
,
const
double
&
lon
,
const
double
&
alt
,
double
*
east
,
double
*
north
,
double
*
up
)
void
HomePosition
Manager
::
wgs84ToEnu
(
const
double
&
lat
,
const
double
&
lon
,
const
double
&
alt
,
double
*
east
,
double
*
north
,
double
*
up
)
{
Eigen
::
Vector3d
ecef
=
wgs84ToEcef
(
lat
,
lon
,
alt
);
Eigen
::
Vector3d
enu
=
ecefToEnu
(
ecef
);
...
...
@@ -193,49 +183,17 @@ void UASManager::wgs84ToEnu(const double& lat, const double& lon, const double&
*
up
=
enu
.
z
();
}
//void UASManager::wgs84ToNed(const double& lat, const double& lon, const double& alt, double* north, double* east, double* down)
//{
//}
void
UASManager
::
enuToWgs84
(
const
double
&
x
,
const
double
&
y
,
const
double
&
z
,
double
*
lat
,
double
*
lon
,
double
*
alt
)
void
HomePositionManager
::
enuToWgs84
(
const
double
&
x
,
const
double
&
y
,
const
double
&
z
,
double
*
lat
,
double
*
lon
,
double
*
alt
)
{
*
lat
=
homeLat
+
y
/
MEAN_EARTH_DIAMETER
*
360.
/
PI
;
*
lon
=
homeLon
+
x
/
MEAN_EARTH_DIAMETER
*
360.
/
PI
/
cos
(
homeLat
*
UMR
);
*
alt
=
homeAlt
+
z
;
}
void
UAS
Manager
::
nedToWgs84
(
const
double
&
x
,
const
double
&
y
,
const
double
&
z
,
double
*
lat
,
double
*
lon
,
double
*
alt
)
void
HomePosition
Manager
::
nedToWgs84
(
const
double
&
x
,
const
double
&
y
,
const
double
&
z
,
double
*
lat
,
double
*
lon
,
double
*
alt
)
{
*
lat
=
homeLat
+
x
/
MEAN_EARTH_DIAMETER
*
360.
/
PI
;
*
lon
=
homeLon
+
y
/
MEAN_EARTH_DIAMETER
*
360.
/
PI
/
cos
(
homeLat
*
UMR
);
*
alt
=
homeAlt
-
z
;
}
/**
* This function will change QGC's home position on a number of conditions only
*/
void
UASManager
::
uavChangedHomePosition
(
int
uav
,
double
lat
,
double
lon
,
double
alt
)
{
// Accept home position changes from the active UAS
if
(
uav
==
MultiVehicleManager
::
instance
()
->
activeVehicle
()
->
id
())
{
if
(
setHomePosition
(
lat
,
lon
,
alt
))
{
// XXX DO NOT UPDATE THE WHOLE FLEET
// foreach (UASInterface* mav, systems)
// {
// // Only update the other systems, not the original source
// if (mav->getUASID() != uav)
// {
// mav->setHomePosition(homeLat, homeLon, homeAlt);
// }
// }
}
}
}
src/
uas/UAS
Manager.h
→
src/
HomePosition
Manager.h
View file @
e79dd41d
...
...
@@ -2,7 +2,7 @@
QGroundControl Open Source Ground Control Station
(c) 2009 - 201
1
QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
(c) 2009 - 201
5
QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
...
...
@@ -21,17 +21,9 @@ This file is part of the QGROUNDCONTROL project
======================================================================*/
/**
* @file
* @brief Definition of class UASManager
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef _UASMANAGER_H_
#define _UASMANAGER_H_
#include "UASManagerInterface.h"
#include "UASInterface.h"
#include <QList>
...
...
@@ -42,17 +34,13 @@ This file is part of the QGROUNDCONTROL project
#include "QGCGeo.h"
#include "QGCSingleton.h"
/**
* @brief Central manager for all connected aerial vehicles
*
* This class keeps a list of all connected / configured UASs. It also stores which
* UAS is currently select with respect to user input or manual controls.
**/
class
UASManager
:
public
UASManagerInterface
/// Manages an offline home position as well as performance coordinate transformations
/// around a home position.
class
HomePositionManager
:
public
QObject
{
Q_OBJECT
DECLARE_QGC_SINGLETON
(
UASManager
,
UASManagerInterface
)
DECLARE_QGC_SINGLETON
(
HomePositionManager
,
HomePositionManager
)
public:
/** @brief Get home position latitude */
...
...
@@ -85,40 +73,6 @@ public:
/** @brief Convert x,y,z coordinates to lat / lon / alt coordinates in north-east-down frame */
void
nedToWgs84
(
const
double
&
x
,
const
double
&
y
,
const
double
&
z
,
double
*
lat
,
double
*
lon
,
double
*
alt
);
void
getLocalNEDSafetyLimits
(
double
*
x1
,
double
*
y1
,
double
*
z1
,
double
*
x2
,
double
*
y2
,
double
*
z2
)
{
*
x1
=
nedSafetyLimitPosition1
.
x
();
*
y1
=
nedSafetyLimitPosition1
.
y
();
*
z1
=
nedSafetyLimitPosition1
.
z
();
*
x2
=
nedSafetyLimitPosition2
.
x
();
*
y2
=
nedSafetyLimitPosition2
.
y
();
*
z2
=
nedSafetyLimitPosition2
.
z
();
}
/** @brief Check if a position is in the local NED safety limits */
bool
isInLocalNEDSafetyLimits
(
double
x
,
double
y
,
double
z
)
{
if
(
x
<
nedSafetyLimitPosition1
.
x
()
&&
y
>
nedSafetyLimitPosition1
.
y
()
&&
z
<
nedSafetyLimitPosition1
.
z
()
&&
x
>
nedSafetyLimitPosition2
.
x
()
&&
y
<
nedSafetyLimitPosition2
.
y
()
&&
z
>
nedSafetyLimitPosition2
.
z
())
{
// Within limits
return
true
;
}
else
{
// Not within limits
return
false
;
}
}
// void wgs84ToNed(const double& lat, const double& lon, const double& alt, double* north, double* east, double* down);
public
slots
:
/** @brief Set the current home position, but do not change it on the UAVs */
bool
setHomePosition
(
double
lat
,
double
lon
,
double
alt
);
...
...
@@ -126,35 +80,30 @@ public slots:
/** @brief Set the current home position on all UAVs*/
bool
setHomePositionAndNotify
(
double
lat
,
double
lon
,
double
alt
);
/** @brief Set the safety limits in local position frame */
void
setLocalNEDSafetyBorders
(
double
x1
,
double
y1
,
double
z1
,
double
x2
,
double
y2
,
double
z2
);
/** @brief Update home position based on the position from one of the UAVs */
void
uavChangedHomePosition
(
int
uav
,
double
lat
,
double
lon
,
double
alt
);
/** @brief Load settings */
void
loadSettings
();
/** @brief Store settings */
void
storeSettings
();
signals:
/** @brief Current home position changed */
void
homePositionChanged
(
double
lat
,
double
lon
,
double
alt
);
protected:
UASWaypointManager
*
offlineUASWaypointManager
;
double
homeLat
;
double
homeLon
;
double
homeAlt
;
int
homeFrame
;
Eigen
::
Quaterniond
ecef_ref_orientation_
;
Eigen
::
Vector3d
ecef_ref_point_
;
Eigen
::
Vector3d
nedSafetyLimitPosition1
;
Eigen
::
Vector3d
nedSafetyLimitPosition2
;
void
initReference
(
const
double
&
latitude
,
const
double
&
longitude
,
const
double
&
altitude
);
private:
/// @brief All access to
UASManager singleton is through UAS
Manager::instance
UAS
Manager
(
QObject
*
parent
=
NULL
);
~
UAS
Manager
();
/// @brief All access to
HomePositionManager singleton is through HomePosition
Manager::instance
HomePosition
Manager
(
QObject
*
parent
=
NULL
);
~
HomePosition
Manager
();
public:
/* Need to align struct pointer to prevent a memory assertion:
...
...
src/QGCApplication.cc
View file @
e79dd41d
...
...
@@ -63,7 +63,7 @@ G_END_DECLS
#endif
#include "QGCSingleton.h"
#include "LinkManager.h"
#include "
UAS
Manager.h"
#include "
HomePosition
Manager.h"
#include "UASMessageHandler.h"
#include "AutoPilotPluginManager.h"
#include "QGCTemporaryFile.h"
...
...
@@ -602,21 +602,21 @@ void QGCApplication::_createSingletons(void)
Q_ASSERT
(
linkManager
);
// Needs LinkManager
UASManagerInterface
*
uasManager
=
UAS
Manager
::
_createSingleton
();
HomePositionManager
*
uasManager
=
HomePosition
Manager
::
_createSingleton
();
Q_UNUSED
(
uasManager
);
Q_ASSERT
(
uasManager
);
// Need
UAS
Manager
// Need
HomePosition
Manager
AutoPilotPluginManager
*
pluginManager
=
AutoPilotPluginManager
::
_createSingleton
();
Q_UNUSED
(
pluginManager
);
Q_ASSERT
(
pluginManager
);
// Need
UAS
Manager
// Need
HomePosition
Manager
UASMessageHandler
*
messageHandler
=
UASMessageHandler
::
_createSingleton
();
Q_UNUSED
(
messageHandler
);
Q_ASSERT
(
messageHandler
);
// Needs
UAS
Manager
// Needs
HomePosition
Manager
FactSystem
*
factSystem
=
FactSystem
::
_createSingleton
();
Q_UNUSED
(
factSystem
);
Q_ASSERT
(
factSystem
);
...
...
@@ -648,7 +648,7 @@ void QGCApplication::_destroySingletons(void)
FactSystem
::
_deleteSingleton
();
UASMessageHandler
::
_deleteSingleton
();
AutoPilotPluginManager
::
_deleteSingleton
();
UAS
Manager
::
_deleteSingleton
();
HomePosition
Manager
::
_deleteSingleton
();
LinkManager
::
_deleteSingleton
();
GAudioOutput
::
_deleteSingleton
();
MultiVehicleManager
::
_deleteSingleton
();
...
...
src/QGCSingleton.h
View file @
e79dd41d
...
...
@@ -36,7 +36,6 @@
/// Include this macro in your Derived Class definition
/// @param className Derived Class name
/// @param interfaceName If your class is accessed through an interface specify that, if not specify Derived class name.
/// For example DECLARE_QGC_SINGLETON(UASManager, UASManagerInterface)
#define DECLARE_QGC_SINGLETON(className, interfaceName) \
public: \
static interfaceName* instance(bool nullOk = false); \
...
...
@@ -54,7 +53,6 @@
/// Include this macro in your Derived Class implementation
/// @param className Derived Class name
/// @param interfaceName If your class is accessed through an interface specify that, if not specify Derived class name.
/// For example DECLARE_QGC_SINGLETON(UASManager, UASManagerInterface)
#define IMPLEMENT_QGC_SINGLETON(className, interfaceName) \
interfaceName* className::_instance = NULL; \
interfaceName* className::_mockInstance = NULL; \
...
...
@@ -114,7 +112,7 @@ class UnitTest;
/// This is done in order to make sure they are all created on the main thread. As such no other code other than Unit Test
/// code has access to the constructor/destructor. QGCSingleton supports replacing singletons with a mock implementation.
/// In this case your object must derive from an interface which in turn derives from QGCSingleton. Youu can then use
/// the setMock method to add and remove you mock implementation. See
UAS
Manager example usage. In order to provide the
/// the setMock method to add and remove you mock implementation. See
HomePosition
Manager example usage. In order to provide the
/// appropriate methods to make all this work you need to use the DECLARE_QGC_SINGLETON and IMPLEMENT_QGC_SINGLETON
/// macros as follows:
/// @code{.unparsed}
...
...
src/VehicleSetup/SetupView.cc
View file @
e79dd41d
...
...
@@ -26,7 +26,6 @@
#include "SetupView.h"
#include "UASManager.h"
#include "AutoPilotPluginManager.h"
#include "VehicleComponent.h"
#include "QGCQmlWidgetHolder.h"
...
...
src/VehicleSetup/SetupViewTest.cc
View file @
e79dd41d
...
...
@@ -28,7 +28,6 @@
#include "MockLink.h"
#include "QGCMessageBox.h"
#include "SetupView.h"
#include "UASManager.h"
#include "MultiVehicleManager.h"
UT_REGISTER_TEST
(
SetupViewTest
)
...
...
src/ViewWidgets/CustomCommandWidgetController.h
View file @
e79dd41d
...
...
@@ -28,7 +28,6 @@
#include "UASInterface.h"
#include "AutoPilotPlugin.h"
#include "UASManagerInterface.h"
#include "FactPanelController.h"
class
CustomCommandWidgetController
:
public
FactPanelController
...
...
src/ViewWidgets/ViewWidgetController.cc
View file @
e79dd41d
...
...
@@ -22,7 +22,6 @@
======================================================================*/
#include "ViewWidgetController.h"
#include "UASManager.h"
#include "MultiVehicleManager.h"
ViewWidgetController
::
ViewWidgetController
(
void
)
:
...
...
src/ViewWidgets/ViewWidgetController.h
View file @
e79dd41d
...
...
@@ -28,7 +28,6 @@
#include "UASInterface.h"
#include "AutoPilotPlugin.h"
#include "UASManagerInterface.h"
#include "Vehicle.h"
class
ViewWidgetController
:
public
QObject
...
...
src/comm/QGCFlightGearLink.cc
View file @
e79dd41d
...
...
@@ -43,6 +43,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGC.h"
#include "QGCFileDialog.h"
#include "QGCMessageBox.h"
#include "HomePositionManager.h"
// FlightGear _fgProcess start and connection is quite fragile. Uncomment the define below to get higher level of debug output
// for tracking down problems.
...
...
@@ -954,11 +955,11 @@ bool QGCFlightGearLink::connectSimulation()
}
// We start out at our home position
_fgArgList
<<
QString
(
"--lat=%1"
).
arg
(
UAS
Manager
::
instance
()
->
getHomeLatitude
());
_fgArgList
<<
QString
(
"--lon=%1"
).
arg
(
UAS
Manager
::
instance
()
->
getHomeLongitude
());
_fgArgList
<<
QString
(
"--lat=%1"
).
arg
(
HomePosition
Manager
::
instance
()
->
getHomeLatitude
());
_fgArgList
<<
QString
(
"--lon=%1"
).
arg
(
HomePosition
Manager
::
instance
()
->
getHomeLongitude
());
// The altitude is not set because an altitude not equal to the ground altitude leads to a non-zero default throttle in flightgear
// Without the altitude-setting the aircraft is positioned on the ground
//_fgArgList << QString("--altitude=%1").arg(
UAS
Manager::instance()->getHomeAltitude());
//_fgArgList << QString("--altitude=%1").arg(
HomePosition
Manager::instance()->getHomeAltitude());
#ifdef DEBUG_FLIGHTGEAR_CONNECT
// This tell FlightGear to output highest debug level of log output. Handy for debuggin failures by looking at the FG
...
...
src/comm/QGCXPlaneLink.cc
View file @
e79dd41d
...
...
@@ -40,6 +40,7 @@ This file is part of the QGROUNDCONTROL project
#include "UAS.h"
#include "UASInterface.h"
#include "QGCMessageBox.h"
#include "HomePositionManager.h"
QGCXPlaneLink
::
QGCXPlaneLink
(
UASInterface
*
mav
,
QString
remoteHost
,
QHostAddress
localHost
,
quint16
localPort
)
:
mav
(
mav
),
...
...
src/uas/UAS.cc
View file @
e79dd41d
...
...
@@ -23,7 +23,7 @@
#include "UAS.h"
#include "LinkInterface.h"
#include "
UAS
Manager.h"
#include "
HomePosition
Manager.h"
#include "QGC.h"
#include "GAudioOutput.h"
#include "MAVLinkProtocol.h"
...
...
@@ -2672,10 +2672,10 @@ void UAS::home()
{
mavlink_message_t
msg
;
double
latitude
=
UAS
Manager
::
instance
()
->
getHomeLatitude
();
double
longitude
=
UAS
Manager
::
instance
()
->
getHomeLongitude
();
double
altitude
=
UAS
Manager
::
instance
()
->
getHomeAltitude
();
int
frame
=
UAS
Manager
::
instance
()
->
getHomeFrame
();
double
latitude
=
HomePosition
Manager
::
instance
()
->
getHomeLatitude
();
double
longitude
=
HomePosition
Manager
::
instance
()
->
getHomeLongitude
();
double
altitude
=
HomePosition
Manager
::
instance
()
->
getHomeAltitude
();
int
frame
=
HomePosition
Manager
::
instance
()
->
getHomeFrame
();
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_ALL
,
MAV_CMD_OVERRIDE_GOTO
,
1
,
MAV_GOTO_DO_CONTINUE
,
MAV_GOTO_HOLD_AT_CURRENT_POSITION
,
frame
,
0
,
latitude
,
longitude
,
altitude
);
_vehicle
->
sendMessage
(
msg
);
...
...
src/uas/UASManagerInterface.h
deleted
100644 → 0
View file @
f10e77cb
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 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/>.
======================================================================*/
/**
* @file
* @brief Definition of class UASManager
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef _UASMANAGERINTERFACE_H_
#define _UASMANAGERINTERFACE_H_
#include <QList>
#include <QMutex>
#include <Eigen/Eigen>
#include "UASInterface.h"
#include "QGCGeo.h"
#include "QGCSingleton.h"
/**
* @brief Central manager for all connected aerial vehicles
*
* This class keeps a list of all connected / configured UASs. It also stores which
* UAS is currently select with respect to user input or manual controls.
*
* This is the abstract base class for UASManager. Although there is normally only
* a single UASManger we still use a abstract base interface since this allows us
* to create mock versions of the UASManager for testing purposes.
*
* See UASManager.h for method documentation
**/
class
UASManagerInterface
:
public
QGCSingleton
{
Q_OBJECT
public:
virtual
double
getHomeLatitude
()
const
=
0
;
virtual
double
getHomeLongitude
()
const
=
0
;
virtual
double
getHomeAltitude
()
const
=
0
;
virtual
int
getHomeFrame
()
const
=
0
;
virtual
Eigen
::
Vector3d
wgs84ToEcef
(
const
double
&
latitude
,
const
double
&
longitude
,
const
double
&
altitude
)
=
0
;
virtual
Eigen
::
Vector3d
ecefToEnu
(
const
Eigen
::
Vector3d
&
ecef
)
=
0
;
virtual
void
wgs84ToEnu
(
const
double
&
lat
,
const
double
&
lon
,
const
double
&
alt
,
double
*
east
,
double
*
north
,
double
*
up
)
=
0
;
virtual
void
enuToWgs84
(
const
double
&
x
,
const
double
&
y
,
const
double
&
z
,
double
*
lat
,
double
*
lon
,
double
*
alt
)
=
0
;
virtual
void
nedToWgs84
(
const
double
&
x
,
const
double
&
y
,
const
double
&
z
,
double
*
lat
,
double
*
lon
,
double
*
alt
)
=
0
;
virtual
void
getLocalNEDSafetyLimits
(
double
*
x1
,
double
*
y1
,
double
*
z1
,
double
*
x2
,
double
*
y2
,
double
*
z2
)
=
0
;
virtual
bool
isInLocalNEDSafetyLimits
(
double
x
,
double
y
,
double
z
)
=
0
;
public
slots
:
virtual
bool
setHomePosition
(
double
lat
,
double
lon
,
double
alt
)
=
0
;
virtual
bool
setHomePositionAndNotify
(
double
lat
,
double
lon
,
double
alt
)
=
0
;
virtual
void
setLocalNEDSafetyBorders
(
double
x1
,
double
y1
,
double
z1
,
double
x2
,
double
y2
,
double
z2
)
=
0
;
virtual
void
uavChangedHomePosition
(
int
uav
,
double
lat
,
double
lon
,
double
alt
)
=
0
;
virtual
void
loadSettings
()
=
0
;
virtual
void
storeSettings
()
=
0
;
signals:
/** @brief Current home position changed */
void
homePositionChanged
(
double
lat
,
double
lon
,
double
alt
);
protected:
UASManagerInterface
(
QObject
*
parent
=
NULL
)
:
QGCSingleton
(
parent
)
{
}
};
#endif // _UASMANAGERINTERFACE_H_
src/uas/UASWaypointManager.cc
View file @
e79dd41d
...
...
@@ -32,7 +32,7 @@ This file is part of the QGROUNDCONTROL project
#include "UASWaypointManager.h"
#include "UAS.h"
#include "mavlink_types.h"
#include "
UAS
Manager.h"
#include "
HomePosition
Manager.h"
#include "QGCMessageBox.h"
#include "Vehicle.h"
...
...
@@ -1164,7 +1164,7 @@ float UASWaypointManager::getAltitudeRecommendation()
if
(
waypointsEditable
.
count
()
>
0
)
{
return
waypointsEditable
.
last
()
->
getAltitude
();
}
else
{
return
UAS
Manager
::
instance
()
->
getHomeAltitude
()
+
getHomeAltitudeOffsetDefault
();
return
HomePosition
Manager
::
instance
()
->
getHomeAltitude
()
+
getHomeAltitudeOffsetDefault
();
}
}
...
...
src/ui/HSIDisplay.cc
View file @
e79dd41d
...
...
@@ -38,7 +38,7 @@ This file is part of the QGROUNDCONTROL project
#include <QDebug>
#include "MultiVehicleManager.h"
#include "
UAS
Manager.h"
#include "
HomePosition
Manager.h"
#include "HSIDisplay.h"
#include "QGC.h"
#include "Waypoint.h"
...
...
@@ -435,11 +435,6 @@ void HSIDisplay::renderOverlay()
paintText
(
str
,
valueColor
,
2.6
f
,
10
,
vheight
-
4.0
f
,
&
painter
);
}
// Draw Safety
double
x1
,
y1
,
z1
,
x2
,
y2
,
z2
;
UASManager
::
instance
()
->
getLocalNEDSafetyLimits
(
&
x1
,
&
y1
,
&
z1
,
&
x2
,
&
y2
,
&
z2
);
// drawSafetyArea(QPointF(x1, y1), QPointF(x2, y2), QGC::colorYellow, painter);
// Draw status message
paintText
(
statusMessage
,
statusColor
,
2.8
f
,
8
,
15
,
&
painter
);
...
...
@@ -1372,7 +1367,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter)
// Transform the lat/lon for this waypoint into the local frame
double
e
,
n
,
u
;
UAS
Manager
::
instance
()
->
wgs84ToEnu
(
w
->
getX
(),
w
->
getY
(),
w
->
getZ
(),
&
e
,
&
n
,
&
u
);
HomePosition
Manager
::
instance
()
->
wgs84ToEnu
(
w
->
getX
(),
w
->
getY
(),
w
->
getZ
(),
&
e
,
&
n
,
&
u
);
in
=
QPointF
(
n
,
e
);
}
// Otherwise we don't process this waypoint.
...
...
src/ui/MAVLinkDecoder.cc
View file @
e79dd41d
#include "MAVLinkDecoder.h"
#include "UASManager.h"
#include <QDebug>
...
...
src/ui/MainWindow.cc
View file @
e79dd41d
...
...
@@ -73,6 +73,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGCDockWidget.h"
#include "MultiVehicleManager.h"
#include "CustomCommandWidget.h"
#include "HomePositionManager.h"
#ifdef UNITTEST_BUILD
#include "QmlControls/QmlTestWidget.h"
...
...
@@ -655,7 +656,7 @@ void MainWindow::closeEvent(QCloseEvent *event)
_storeCurrentViewState
();
storeSettings
();
UAS
Manager
::
instance
()
->
storeSettings
();
HomePosition
Manager
::
instance
()
->
storeSettings
();
event
->
accept
();
}
...
...
src/ui/MainWindow.h
View file @
e79dd41d
...
...
@@ -41,7 +41,6 @@ This file is part of the QGROUNDCONTROL project
#include "LinkManager.h"
#include "LinkInterface.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "UASControlWidget.h"
#include "UASInfoWidget.h"
#include "WaypointList.h"
...
...
src/ui/WaypointList.cc
View file @
e79dd41d
...
...
@@ -37,7 +37,7 @@ This file is part of the PIXHAWK project
#include <UASInterface.h>
#include <UAS.h>
#include <
UAS
Manager.h>
#include <
HomePosition
Manager.h>
#include <QDebug>
#include <QMouseEvent>
#include <QTextEdit>
...
...
@@ -314,8 +314,8 @@ void WaypointList::addEditable(bool onCurrentPosition)
}
else
{
updateStatusLabel
(
tr
(
"Added default GLOBAL (Relative alt.) waypoint."
));
}
wp
=
new
Waypoint
(
0
,
UAS
Manager
::
instance
()
->
getHomeLatitude
(),
UAS
Manager
::
instance
()
->
getHomeLongitude
(),
wp
=
new
Waypoint
(
0
,
HomePosition
Manager
::
instance
()
->
getHomeLatitude
(),
HomePosition
Manager
::
instance
()
->
getHomeLongitude
(),
WPM
->
getAltitudeRecommendation
(),
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
(
MAV_FRAME
)
WPM
->
getFrameRecommendation
(),
MAV_CMD_NAV_WAYPOINT
);
WPM
->
addWaypointEditable
(
wp
);
}
...
...
@@ -337,8 +337,8 @@ void WaypointList::addEditable(bool onCurrentPosition)
{
// MAV connected, but position unknown, add default waypoint
updateStatusLabel
(
tr
(
"WARNING: No position known. Adding default LOCAL (NED) waypoint"
));
wp
=
new
Waypoint
(
0
,
UAS
Manager
::
instance
()
->
getHomeLatitude
(),
UAS
Manager
::
instance
()
->
getHomeLongitude
(),
wp
=
new
Waypoint
(
0
,
HomePosition
Manager
::
instance
()
->
getHomeLatitude
(),
HomePosition
Manager
::
instance
()
->
getHomeLongitude
(),
WPM
->
getAltitudeRecommendation
(),
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
(
MAV_FRAME
)
WPM
->
getFrameRecommendation
(),
MAV_CMD_NAV_WAYPOINT
);
WPM
->
addWaypointEditable
(
wp
);
}
...
...
@@ -347,8 +347,8 @@ void WaypointList::addEditable(bool onCurrentPosition)
{
//Since no UAV available, create first default waypoint.
updateStatusLabel
(
tr
(
"No UAV connected. Adding default GLOBAL (NED) waypoint"
));
wp
=
new
Waypoint
(
0
,
UAS
Manager
::
instance
()
->
getHomeLatitude
(),
UAS
Manager
::
instance
()
->
getHomeLongitude
(),
wp
=
new
Waypoint
(
0
,
HomePosition
Manager
::
instance
()
->
getHomeLatitude
(),
HomePosition
Manager
::
instance
()
->
getHomeLongitude
(),
WPM
->
getAltitudeRecommendation
(),
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
(
MAV_FRAME
)
WPM
->
getFrameRecommendation
(),
MAV_CMD_NAV_WAYPOINT
);
WPM
->
addWaypointEditable
(
wp
);
}
...
...
src/ui/map/QGCMapWidget.cc
View file @
e79dd41d
...
...
@@ -2,7 +2,7 @@
#include "QGCMapWidget.h"
#include "QGCMapToolBar.h"
#include "UASInterface.h"
#include "
UAS
Manager.h"
#include "
HomePosition
Manager.h"
#include "MAV2DIcon.h"
#include "Waypoint2DIcon.h"
#include "UASWaypointManager.h"
...
...
@@ -123,7 +123,7 @@ bool QGCMapWidget::setHomeActionTriggered()
QGCMessageBox
::
information
(
tr
(
"Error"
),
tr
(
"Please connect first"
));
return
false
;
}
UASManagerInterface
*
uasManager
=
UAS
Manager
::
instance
();
HomePositionManager
*
uasManager
=
HomePosition
Manager
::
instance
();
if
(
!
uasManager
)
{
return
false
;
}
// Enter an altitude
...
...
@@ -187,7 +187,7 @@ void QGCMapWidget::showEvent(QShowEvent* event)
connect
(
MultiVehicleManager
::
instance
(),
&
MultiVehicleManager
::
vehicleAdded
,
this
,
&
QGCMapWidget
::
_vehicleAdded
);
connect
(
MultiVehicleManager
::
instance
(),
&
MultiVehicleManager
::
activeVehicleChanged
,
this
,
&
QGCMapWidget
::
_activeVehicleChanged
);
connect
(
UAS
Manager
::
instance
(),
SIGNAL
(
homePositionChanged
(
double
,
double
,
double
)),
this
,
SLOT
(
updateHomePosition
(
double
,
double
,
double
)),
Qt
::
UniqueConnection
);
connect
(
HomePosition
Manager
::
instance
(),
SIGNAL
(
homePositionChanged
(
double
,
double
,
double
)),
this
,
SLOT
(
updateHomePosition
(
double
,
double
,
double
)),
Qt
::
UniqueConnection
);
foreach
(
Vehicle
*
vehicle
,
MultiVehicleManager
::
instance
()
->
vehicles
())
{
_vehicleAdded
(
vehicle
);
...
...
@@ -213,7 +213,7 @@ void QGCMapWidget::showEvent(QShowEvent* event)
}
// Set home
updateHomePosition
(
UASManager
::
instance
()
->
getHomeLatitude
(),
UASManager
::
instance
()
->
getHomeLongitude
(),
UAS
Manager
::
instance
()
->
getHomeAltitude
());
updateHomePosition
(
HomePositionManager
::
instance
()
->
getHomeLatitude
(),
HomePositionManager
::
instance
()
->
getHomeLongitude
(),
HomePosition
Manager
::
instance
()
->
getHomeAltitude
());
// Set currently selected system
_activeVehicleChanged
(
MultiVehicleManager
::
instance
()
->
activeVehicle
());
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment