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
3c252685
Commit
3c252685
authored
Jan 05, 2018
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Use default minimum takeoff alt for guided takeoff
parent
890b0a5e
Changes
9
Hide whitespace changes
Inline
Side-by-side
Showing
9 changed files
with
48 additions
and
22 deletions
+48
-22
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+13
-14
APMFirmwarePlugin.h
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+1
-0
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+3
-0
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+13
-7
PX4FirmwarePlugin.h
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
+1
-0
GuidedActionsController.qml
src/FlightDisplay/GuidedActionsController.qml
+1
-1
GuidedAltitudeSlider.qml
src/FlightDisplay/GuidedAltitudeSlider.qml
+8
-0
Vehicle.cc
src/Vehicle/Vehicle.cc
+5
-0
Vehicle.h
src/Vehicle/Vehicle.h
+3
-0
No files found.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
3c252685
...
...
@@ -911,6 +911,18 @@ void APMFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double altitudeRel)
_guidedModeTakeoff
(
vehicle
,
altitudeRel
);
}
double
APMFirmwarePlugin
::
minimumTakeoffAltitude
(
Vehicle
*
vehicle
)
{
QString
takeoffAltParam
(
vehicle
->
vtol
()
?
QStringLiteral
(
"Q_RTL_ALT"
)
:
QStringLiteral
(
"PILOT_TKOFF_ALT"
));
float
paramDivisor
=
vehicle
->
vtol
()
?
1.0
:
100.0
;
// PILOT_TAKEOFF_ALT is in centimeters
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
))
{
return
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
)
->
rawValue
().
toDouble
()
/
paramDivisor
;
}
else
{
return
FirmwarePlugin
::
minimumTakeoffAltitude
(
vehicle
);
}
}
bool
APMFirmwarePlugin
::
_guidedModeTakeoff
(
Vehicle
*
vehicle
,
double
altitudeRel
)
{
if
(
!
vehicle
->
multiRotor
()
&&
!
vehicle
->
vtol
())
{
...
...
@@ -924,20 +936,7 @@ bool APMFirmwarePlugin::_guidedModeTakeoff(Vehicle* vehicle, double altitudeRel)
return
false
;
}
QString
takeoffAltParam
(
vehicle
->
vtol
()
?
QStringLiteral
(
"Q_RTL_ALT"
)
:
QStringLiteral
(
"PILOT_TKOFF_ALT"
));
float
paramDivisor
=
vehicle
->
vtol
()
?
1.0
:
100.0
;
// PILOT_TAKEOFF_ALT is in centimeters
float
takeoffAltRel
=
0
;
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
))
{
Fact
*
takeoffAltFact
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
);
takeoffAltRel
=
takeoffAltFact
->
rawValue
().
toDouble
();
}
if
(
takeoffAltRel
<=
0
)
{
takeoffAltRel
=
2.5
;
}
else
{
takeoffAltRel
/=
paramDivisor
;
// centimeters -> meters
}
double
takeoffAltRel
=
minimumTakeoffAltitude
(
vehicle
);
if
(
!
qIsNaN
(
altitudeRel
)
&&
altitudeRel
>
takeoffAltRel
)
{
takeoffAltRel
=
altitudeRel
;
}
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
3c252685
...
...
@@ -78,6 +78,7 @@ public:
void
setGuidedMode
(
Vehicle
*
vehicle
,
bool
guidedMode
)
override
;
void
guidedModeTakeoff
(
Vehicle
*
vehicle
,
double
altitudeRel
)
override
;
void
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
)
override
;
double
minimumTakeoffAltitude
(
Vehicle
*
vehicle
)
override
;
void
startMission
(
Vehicle
*
vehicle
)
override
;
QStringList
flightModes
(
Vehicle
*
vehicle
)
override
;
QString
flightMode
(
uint8_t
base_mode
,
uint32_t
custom_mode
)
const
override
;
...
...
src/FirmwarePlugin/FirmwarePlugin.h
View file @
3c252685
...
...
@@ -130,6 +130,9 @@ public:
/// Command vehicle to takeoff from current location to a firmware specific height.
virtual
void
guidedModeTakeoff
(
Vehicle
*
vehicle
,
double
takeoffAltRel
);
/// @return The minimum takeoff altitude (relative) for guided takeoff.
virtual
double
minimumTakeoffAltitude
(
Vehicle
*
vehicle
)
{
Q_UNUSED
(
vehicle
);
return
10
;
}
/// Command the vehicle to start the mission
virtual
void
startMission
(
Vehicle
*
vehicle
);
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
3c252685
...
...
@@ -384,24 +384,30 @@ void PX4FirmwarePlugin::_mavCommandResult(int vehicleId, int component, int comm
}
}
void
PX4FirmwarePlugin
::
guidedModeTakeoff
(
Vehicle
*
vehicle
,
double
takeoffAltRel
)
double
PX4FirmwarePlugin
::
minimumTakeoffAltitude
(
Vehicle
*
vehicle
)
{
QString
takeoffAltParam
(
"MIS_TAKEOFF_ALT"
);
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
))
{
return
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
)
->
rawValue
().
toDouble
();
}
else
{
return
FirmwarePlugin
::
minimumTakeoffAltitude
(
vehicle
);
}
}
void
PX4FirmwarePlugin
::
guidedModeTakeoff
(
Vehicle
*
vehicle
,
double
takeoffAltRel
)
{
double
vehicleAltitudeAMSL
=
vehicle
->
altitudeAMSL
()
->
rawValue
().
toDouble
();
if
(
qIsNaN
(
vehicleAltitudeAMSL
))
{
qgcApp
()
->
showMessage
(
tr
(
"Unable to takeoff, vehicle position not known."
));
return
;
}
if
(
!
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
))
{
qgcApp
()
->
showMessage
(
tr
(
"Unable to takeoff, MIS_TAKEOFF_ALT parameter missing."
));
return
;
}
double
takeoffAltRelFromVehicle
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
)
->
rawValue
().
toDouble
();
double
takeoffAltRelFromVehicle
=
minimumTakeoffAltitude
(
vehicle
);
double
takeoffAltAMSL
=
qMax
(
takeoffAltRel
,
takeoffAltRelFromVehicle
)
+
vehicleAltitudeAMSL
;
qDebug
()
<<
takeoffAltRel
<<
takeoffAltRelFromVehicle
<<
takeoffAltAMSL
<<
vehicleAltitudeAMSL
;
connect
(
vehicle
,
&
Vehicle
::
mavCommandResult
,
this
,
&
PX4FirmwarePlugin
::
_mavCommandResult
);
vehicle
->
sendMavCommand
(
vehicle
->
defaultComponentId
(),
MAV_CMD_NAV_TAKEOFF
,
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
View file @
3c252685
...
...
@@ -49,6 +49,7 @@ public:
void
guidedModeOrbit
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
centerCoord
=
QGeoCoordinate
(),
double
radius
=
NAN
,
double
velocity
=
NAN
,
double
altitude
=
NAN
)
override
;
void
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
)
override
;
void
guidedModeChangeAltitude
(
Vehicle
*
vehicle
,
double
altitudeRel
)
override
;
double
minimumTakeoffAltitude
(
Vehicle
*
vehicle
)
override
;
void
startMission
(
Vehicle
*
vehicle
)
override
;
bool
isGuidedMode
(
const
Vehicle
*
vehicle
)
const
override
;
int
manualControlReservedButtonCount
(
void
)
override
;
...
...
src/FlightDisplay/GuidedActionsController.qml
View file @
3c252685
...
...
@@ -213,7 +213,7 @@ Item {
confirmDialog
.
title
=
takeoffTitle
confirmDialog
.
message
=
takeoffMessage
confirmDialog
.
hideTrigger
=
Qt
.
binding
(
function
()
{
return
!
showTakeoff
})
altitudeSlider
.
reset
()
altitudeSlider
.
setToMinimumTakeoff
()
altitudeSlider
.
visible
=
true
break
;
case
actionStartMission
:
...
...
src/FlightDisplay/GuidedAltitudeSlider.qml
View file @
3c252685
...
...
@@ -32,6 +32,10 @@ Rectangle {
altSlider
.
value
=
0
}
function
setToMinimumTakeoff
()
{
altField
.
setToMinimumTakeoff
()
}
function
getValue
()
{
return
altField
.
newAltitudeMeters
-
_vehicleAltitude
}
...
...
@@ -70,6 +74,10 @@ Rectangle {
property
real
altLossGain
:
altExp
*
(
altSlider
.
value
>
0
?
altGainRange
:
altLossRange
)
property
real
newAltitudeMeters
:
_vehicleAltitude
+
altLossGain
property
string
newAltitudeAppUnits
:
QGroundControl
.
metersToAppSettingsDistanceUnits
(
newAltitudeMeters
).
toFixed
(
1
)
function
setToMinimumTakeoff
()
{
altSlider
.
value
=
Math
.
pow
(
_activeVehicle
.
minimumTakeoffAltitude
()
/
altGainRange
,
1.0
/
3.0
)
}
}
}
...
...
src/Vehicle/Vehicle.cc
View file @
3c252685
...
...
@@ -2266,6 +2266,11 @@ void Vehicle::guidedModeTakeoff(double altitudeRelative)
_firmwarePlugin
->
guidedModeTakeoff
(
this
,
altitudeRelative
);
}
double
Vehicle
::
minimumTakeoffAltitude
(
void
)
{
return
_firmwarePlugin
->
minimumTakeoffAltitude
(
this
);
}
void
Vehicle
::
startMission
(
void
)
{
_firmwarePlugin
->
startMission
(
this
);
...
...
src/Vehicle/Vehicle.h
View file @
3c252685
...
...
@@ -423,6 +423,9 @@ public:
/// Command vehicle to takeoff from current location
Q_INVOKABLE
void
guidedModeTakeoff
(
double
altitudeRelative
);
/// @return The minimum takeoff altitude (relative) for guided takeoff.
Q_INVOKABLE
double
minimumTakeoffAltitude
(
void
);
/// Command vehicle to move to specified location (altitude is included and relative)
Q_INVOKABLE
void
guidedModeGotoLocation
(
const
QGeoCoordinate
&
gotoCoord
);
...
...
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