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
60a46a22
Commit
60a46a22
authored
Oct 24, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #2106 from DonLakeFlyer/MissionHomeMove
Mission home move
parents
982e4d06
957710b4
Changes
8
Hide whitespace changes
Inline
Side-by-side
Showing
8 changed files
with
61 additions
and
47 deletions
+61
-47
FlightDisplayView.qml
src/FlightDisplay/FlightDisplayView.qml
+1
-1
FlightDisplayViewDelayLoadInner.qml
src/FlightDisplay/FlightDisplayViewDelayLoadInner.qml
+1
-2
VehicleMapItem.qml
src/FlightMap/MapItems/VehicleMapItem.qml
+1
-1
QGCCompassWidget.qml
src/FlightMap/Widgets/QGCCompassWidget.qml
+1
-4
MissionEditor.qml
src/MissionEditor/MissionEditor.qml
+15
-1
Vehicle.cc
src/Vehicle/Vehicle.cc
+16
-14
Vehicle.h
src/Vehicle/Vehicle.h
+22
-23
UAS.cc
src/uas/UAS.cc
+4
-1
No files found.
src/FlightDisplay/FlightDisplayView.qml
View file @
60a46a22
...
...
@@ -73,7 +73,7 @@ Item {
property
real
_pitch
:
_activeVehicle
?
(
isNaN
(
_activeVehicle
.
pitch
)
?
_defaultPitch
:
_activeVehicle
.
pitch
)
:
_defaultPitch
property
real
_heading
:
_activeVehicle
?
(
isNaN
(
_activeVehicle
.
heading
)
?
_defaultHeading
:
_activeVehicle
.
heading
)
:
_defaultHeading
property
var
_vehicleCoordinate
:
_activeVehicle
?
(
_activeVehicle
.
satelliteLock
>=
2
?
_activeVehicle
.
coordinate
:
_defaultVehicleCoordinate
)
:
_defaultVehicleCoordinate
property
var
_vehicleCoordinate
:
_activeVehicle
?
(
_activeVehicle
.
coordinateValid
?
_activeVehicle
.
coordinate
:
_defaultVehicleCoordinate
)
:
_defaultVehicleCoordinate
property
real
_altitudeWGS84
:
_activeVehicle
?
_activeVehicle
.
altitudeWGS84
:
_defaultAltitudeWGS84
property
real
_groundSpeed
:
_activeVehicle
?
_activeVehicle
.
groundSpeed
:
_defaultGroundSpeed
...
...
src/FlightDisplay/FlightDisplayViewDelayLoadInner.qml
View file @
60a46a22
...
...
@@ -51,7 +51,7 @@ Item {
QGCLabel
{
width
:
gpsLockColumn
.
width
horizontalAlignment
:
Text
.
AlignHCenter
visible
:
object
.
satelliteLock
<
2
visible
:
!
object
.
coordinateValid
text
:
"
No GPS Lock for Vehicle #
"
+
object
.
id
z
:
QGroundControl
.
zOrderMapItems
-
2
}
...
...
@@ -65,7 +65,6 @@ Item {
anchors.top
:
parent
.
top
size
:
ScreenTools
.
defaultFontPixelSize
*
(
13.3
)
heading
:
_heading
active
:
multiVehicleManager
.
activeVehicleAvailable
z
:
QGroundControl
.
zOrderWidgets
}
...
...
src/FlightMap/MapItems/VehicleMapItem.qml
View file @
60a46a22
...
...
@@ -38,7 +38,7 @@ MapQuickItem {
anchorPoint.x
:
vehicleIcon
.
width
/
2
anchorPoint.y
:
vehicleIcon
.
height
/
2
visible
:
vehicle
.
satelliteLock
>=
2
// 2D lock
visible
:
vehicle
.
coordinateValid
sourceItem
:
Image
{
id
:
vehicleIcon
...
...
src/FlightMap/Widgets/QGCCompassWidget.qml
View file @
60a46a22
...
...
@@ -34,15 +34,12 @@ import QGroundControl.ScreenTools 1.0
QGCMovableItem
{
id
:
root
property
bool
active
:
false
///< true: actively connected to data provider, false: show inactive control
property
real
heading
:
_defaultHeading
property
real
size
:
ScreenTools
.
defaultFontPixelSize
*
(
10
)
property
int
_fontSize
:
ScreenTools
.
defaultFontPixelSize
readonly
property
real
_defaultHeading
:
0
property
real
_heading
:
active
?
heading
:
_defaultHeading
width
:
size
height
:
size
Rectangle
{
...
...
@@ -60,7 +57,7 @@ QGCMovableItem {
transform
:
Rotation
{
origin.x
:
pointer
.
width
/
2
origin.y
:
pointer
.
height
/
2
angle
:
_
heading
angle
:
heading
}
}
Image
{
...
...
src/MissionEditor/MissionEditor.qml
View file @
60a46a22
...
...
@@ -56,7 +56,10 @@ QGCView {
readonly
property
int
_addMissionItemsButtonAutoOffTimeout
:
10000
readonly
property
var
_defaultVehicleCoordinate
:
QtPositioning
.
coordinate
(
37.803784
,
-
122.462276
)
property
var
_missionItems
:
controller
.
missionItems
property
var
_missionItems
:
controller
.
missionItems
property
bool
gpsLock
:
_activeVehicle
?
_activeVehicle
.
coordinateValid
:
false
property
bool
_firstGpsLock
:
true
//property var _homePositionManager: QGroundControl.homePositionManager
//property string _homePositionName: _homePositionManager.homePositions.get(0).name
...
...
@@ -71,6 +74,17 @@ QGCView {
property
bool
_showHelp
:
QGroundControl
.
flightMapSettings
.
loadBoolMapSetting
(
editorMap
.
mapName
,
_showHelpKey
,
true
)
onGpsLockChanged
:
updateMapToVehiclePosition
()
Component.onCompleted
:
updateMapToVehiclePosition
()
function
updateMapToVehiclePosition
()
{
if
(
gpsLock
&&
_firstGpsLock
)
{
_firstGpsLock
=
false
editorMap
.
latitude
=
_activeVehicle
.
latitude
editorMap
.
longitude
=
_activeVehicle
.
longitude
}
}
MissionController
{
id
:
controller
...
...
src/Vehicle/Vehicle.cc
View file @
60a46a22
...
...
@@ -53,6 +53,8 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType,
,
_joystickMode
(
JoystickModeRC
)
,
_joystickEnabled
(
false
)
,
_uas
(
NULL
)
,
_coordinate
(
37.803784
,
-
122.462276
)
,
_coordinateValid
(
false
)
,
_homePositionAvailable
(
false
)
,
_mav
(
NULL
)
,
_currentMessageCount
(
0
)
...
...
@@ -74,8 +76,6 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType,
,
_navigationSpeedError
(
0.0
f
)
,
_navigationCrosstrackError
(
0.0
f
)
,
_navigationTargetBearing
(
0.0
f
)
,
_latitude
(
DEFAULT_LAT
)
,
_longitude
(
DEFAULT_LON
)
,
_refreshTimer
(
new
QTimer
(
this
))
,
_batteryVoltage
(
-
1.0
f
)
,
_batteryPercent
(
0.0
)
...
...
@@ -322,13 +322,13 @@ QList<LinkInterface*> Vehicle::links(void)
void
Vehicle
::
setLatitude
(
double
latitude
)
{
_
geoC
oordinate
.
setLatitude
(
latitude
);
emit
coordinateChanged
(
_
geoC
oordinate
);
_
c
oordinate
.
setLatitude
(
latitude
);
emit
coordinateChanged
(
_
c
oordinate
);
}
void
Vehicle
::
setLongitude
(
double
longitude
){
_
geoC
oordinate
.
setLongitude
(
longitude
);
emit
coordinateChanged
(
_
geoC
oordinate
);
_
c
oordinate
.
setLongitude
(
longitude
);
emit
coordinateChanged
(
_
c
oordinate
);
}
void
Vehicle
::
_updateAttitude
(
UASInterface
*
,
double
roll
,
double
pitch
,
double
yaw
,
quint64
)
...
...
@@ -498,13 +498,11 @@ void Vehicle::_checkUpdate()
{
// Update current location
if
(
_mav
)
{
if
(
_latitude
!=
_mav
->
getLatitude
())
{
_latitude
=
_mav
->
getLatitude
();
emit
latitudeChanged
();
if
(
latitude
()
!=
_mav
->
getLatitude
())
{
setLatitude
(
_mav
->
getLatitude
());
}
if
(
_longitude
!=
_mav
->
getLongitude
())
{
_longitude
=
_mav
->
getLongitude
();
emit
longitudeChanged
();
if
(
longitude
()
!=
_mav
->
getLongitude
())
{
setLongitude
(
_mav
->
getLongitude
());
}
}
// The timer rate is 20Hz for the coordinates above. These below we only check
...
...
@@ -705,6 +703,10 @@ void Vehicle::_setSatLoc(UASInterface*, int fix)
{
// fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D lock, 3: 3D lock
if
(
_satelliteLock
!=
fix
)
{
if
(
fix
>
2
)
{
_coordinateValid
=
true
;
emit
coordinateValidChanged
(
true
);
}
_satelliteLock
=
fix
;
emit
satelliteLockChanged
();
}
...
...
@@ -1086,10 +1088,10 @@ void Vehicle::_missionManagerError(int errorCode, const QString& errorMsg)
void
Vehicle
::
_addNewMapTrajectoryPoint
(
void
)
{
if
(
_mapTrajectoryHaveFirstCoordinate
)
{
_mapTrajectoryList
.
append
(
new
CoordinateVector
(
_mapTrajectoryLastCoordinate
,
_
geoC
oordinate
,
this
));
_mapTrajectoryList
.
append
(
new
CoordinateVector
(
_mapTrajectoryLastCoordinate
,
_
c
oordinate
,
this
));
}
_mapTrajectoryHaveFirstCoordinate
=
true
;
_mapTrajectoryLastCoordinate
=
_
geoC
oordinate
;
_mapTrajectoryLastCoordinate
=
_
c
oordinate
;
}
void
Vehicle
::
_mapTrajectoryStart
(
void
)
...
...
src/Vehicle/Vehicle.h
View file @
60a46a22
...
...
@@ -56,23 +56,23 @@ public:
Q_PROPERTY
(
int
id
READ
id
CONSTANT
)
Q_PROPERTY
(
AutoPilotPlugin
*
autopilot
MEMBER
_autopilotPlugin
CONSTANT
)
Q_PROPERTY
(
QGeoCoordinate
coordinate
MEMBER
_geoCoordinate
NOTIFY
coordinateChanged
)
Q_PROPERTY
(
MissionManager
*
missionManager
MEMBER
_missionManager
CONSTANT
)
Q_PROPERTY
(
bool
homePositionAvailable
READ
homePositionAvailable
NOTIFY
homePositionAvailableChanged
)
Q_PROPERTY
(
QGeoCoordinate
homePosition
READ
homePosition
NOTIFY
homePositionChanged
)
Q_PROPERTY
(
bool
armed
READ
armed
WRITE
setArmed
NOTIFY
armedChanged
)
Q_PROPERTY
(
QGeoCoordinate
coordinate
READ
coordinate
NOTIFY
coordinateChanged
)
Q_PROPERTY
(
bool
coordinateValid
READ
coordinateValid
NOTIFY
coordinateValidChanged
)
Q_PROPERTY
(
MissionManager
*
missionManager
MEMBER
_missionManager
CONSTANT
)
Q_PROPERTY
(
bool
homePositionAvailable
READ
homePositionAvailable
NOTIFY
homePositionAvailableChanged
)
Q_PROPERTY
(
QGeoCoordinate
homePosition
READ
homePosition
NOTIFY
homePositionChanged
)
Q_PROPERTY
(
bool
armed
READ
armed
WRITE
setArmed
NOTIFY
armedChanged
)
Q_PROPERTY
(
bool
flightModeSetAvailable
READ
flightModeSetAvailable
CONSTANT
)
Q_PROPERTY
(
QStringList
flightModes
READ
flightModes
CONSTANT
)
Q_PROPERTY
(
QString
flightMode
READ
flightMode
WRITE
setFlightMode
NOTIFY
flightModeChanged
)
Q_PROPERTY
(
bool
hilMode
READ
hilMode
WRITE
setHilMode
NOTIFY
hilModeChanged
)
Q_PROPERTY
(
bool
missingParameters
READ
missingParameters
NOTIFY
missingParametersChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
trajectoryPoints
READ
trajectoryPoints
CONSTANT
)
Q_PROPERTY
(
bool
flightModeSetAvailable
READ
flightModeSetAvailable
CONSTANT
)
Q_PROPERTY
(
QStringList
flightModes
READ
flightModes
CONSTANT
)
Q_PROPERTY
(
QString
flightMode
READ
flightMode
WRITE
setFlightMode
NOTIFY
flightModeChanged
)
// Property accessors
Q_PROPERTY
(
bool
hilMode
READ
hilMode
WRITE
setHilMode
NOTIFY
hilModeChanged
)
Q_PROPERTY
(
bool
missingParameters
READ
missingParameters
NOTIFY
missingParametersChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
trajectoryPoints
READ
trajectoryPoints
CONSTANT
)
QGeoCoordinate
coordinate
(
void
)
{
return
_coordinate
;
}
bool
coordinateValid
(
void
)
{
return
_coordinateValid
;
}
Q_INVOKABLE
QString
getMavIconColor
();
...
...
@@ -94,8 +94,8 @@ public:
Q_PROPERTY
(
float
altitudeRelative
READ
altitudeRelative
NOTIFY
altitudeRelativeChanged
)
Q_PROPERTY
(
float
altitudeWGS84
READ
altitudeWGS84
NOTIFY
altitudeWGS84Changed
)
Q_PROPERTY
(
float
altitudeAMSL
READ
altitudeAMSL
NOTIFY
altitudeAMSLChanged
)
Q_PROPERTY
(
float
latitude
READ
latitude
NOTIFY
latitud
eChanged
)
Q_PROPERTY
(
float
longitude
READ
longitude
NOTIFY
longitud
eChanged
)
Q_PROPERTY
(
float
latitude
READ
latitude
NOTIFY
coordinat
eChanged
)
Q_PROPERTY
(
float
longitude
READ
longitude
NOTIFY
coordinat
eChanged
)
Q_PROPERTY
(
double
batteryVoltage
READ
batteryVoltage
NOTIFY
batteryVoltageChanged
)
Q_PROPERTY
(
double
batteryPercent
READ
batteryPercent
NOTIFY
batteryPercentChanged
)
Q_PROPERTY
(
double
batteryConsumed
READ
batteryConsumed
NOTIFY
batteryConsumedChanged
)
...
...
@@ -234,8 +234,8 @@ public:
float
altitudeRelative
()
{
return
_altitudeRelative
;
}
float
altitudeWGS84
()
{
return
_altitudeWGS84
;
}
float
altitudeAMSL
()
{
return
_altitudeAMSL
;
}
float
latitude
()
{
return
_
latitude
;
}
float
longitude
()
{
return
_
longitude
;
}
float
latitude
()
{
return
_
coordinate
.
latitude
()
;
}
float
longitude
()
{
return
_
coordinate
.
longitude
()
;
}
bool
mavPresent
()
{
return
_mav
!=
NULL
;
}
int
satelliteCount
()
{
return
_satelliteCount
;
}
double
batteryVoltage
()
{
return
_batteryVoltage
;
}
...
...
@@ -256,6 +256,7 @@ public slots:
signals:
void
allLinksDisconnected
(
Vehicle
*
vehicle
);
void
coordinateChanged
(
QGeoCoordinate
coordinate
);
void
coordinateValidChanged
(
bool
coordinateValid
);
void
joystickModeChanged
(
int
mode
);
void
joystickEnabledChanged
(
bool
enabled
);
void
activeChanged
(
bool
active
);
...
...
@@ -283,7 +284,6 @@ signals:
void
altitudeRelativeChanged
();
void
altitudeWGS84Changed
();
void
altitudeAMSLChanged
();
void
latitudeChanged
();
void
longitudeChanged
();
void
batteryVoltageChanged
();
void
batteryPercentChanged
();
...
...
@@ -366,7 +366,8 @@ private:
UAS
*
_uas
;
QGeoCoordinate
_geoCoordinate
;
QGeoCoordinate
_coordinate
;
bool
_coordinateValid
;
///< true: vehicle has 3d lock and therefore valid location
bool
_homePositionAvailable
;
QGeoCoordinate
_homePosition
;
...
...
@@ -392,8 +393,6 @@ private:
float
_navigationSpeedError
;
float
_navigationCrosstrackError
;
float
_navigationTargetBearing
;
float
_latitude
;
float
_longitude
;
QTimer
*
_refreshTimer
;
QList
<
int
>
_changes
;
double
_batteryVoltage
;
...
...
src/uas/UAS.cc
View file @
60a46a22
...
...
@@ -758,7 +758,6 @@ void UAS::receiveMessage(mavlink_message_t message)
{
loc_type
=
0
;
}
emit
localizationChanged
(
this
,
loc_type
);
setSatelliteCount
(
pos
.
satellites_visible
);
if
(
pos
.
fix_type
>
2
)
...
...
@@ -788,6 +787,10 @@ void UAS::receiveMessage(mavlink_message_t message)
}
}
}
// Emit this signal after the above signals. This way a trigger on gps lock signal which then asks for vehicle position
// gets a good position.
emit
localizationChanged
(
this
,
loc_type
);
}
break
;
case
MAVLINK_MSG_ID_GPS_STATUS
:
...
...
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