Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
8484d079
Commit
8484d079
authored
May 14, 2017
by
Don Gagne
Browse files
Takeoff uses PILOT_TAKEOFF_ALT and ui validation only
parent
120781ae
Changes
1
Hide whitespace changes
Inline
Side-by-side
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
8484d079
...
@@ -172,6 +172,20 @@ void ArduCopterFirmwarePlugin::guidedModeLand(Vehicle* vehicle)
...
@@ -172,6 +172,20 @@ void ArduCopterFirmwarePlugin::guidedModeLand(Vehicle* vehicle)
void
ArduCopterFirmwarePlugin
::
guidedModeTakeoff
(
Vehicle
*
vehicle
)
void
ArduCopterFirmwarePlugin
::
guidedModeTakeoff
(
Vehicle
*
vehicle
)
{
{
QString
takeoffAltParam
(
"PILOT_TKOFF_ALT"
);
if
(
!
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
))
{
qgcApp
()
->
showMessage
(
tr
(
"Unable to takeoff, %1 parameter missing."
).
arg
(
takeoffAltParam
));
return
;
}
Fact
*
takeoffAltFact
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
);
float
takeoffAlt
=
takeoffAltFact
->
rawValue
().
toDouble
();
if
(
takeoffAlt
<=
0
)
{
takeoffAlt
=
2.5
;
}
else
{
takeoffAlt
/=
100
;
// centimeters -> meters
}
if
(
!
_armVehicleAndValidate
(
vehicle
))
{
if
(
!
_armVehicleAndValidate
(
vehicle
))
{
qgcApp
()
->
showMessage
(
tr
(
"Unable to takeoff: Vehicle failed to arm."
));
qgcApp
()
->
showMessage
(
tr
(
"Unable to takeoff: Vehicle failed to arm."
));
return
;
return
;
...
@@ -181,7 +195,7 @@ void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle)
...
@@ -181,7 +195,7 @@ void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle)
MAV_CMD_NAV_TAKEOFF
,
MAV_CMD_NAV_TAKEOFF
,
true
,
// show error
true
,
// show error
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
,
2.5
);
takeoffAlt
);
}
}
void
ArduCopterFirmwarePlugin
::
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
)
void
ArduCopterFirmwarePlugin
::
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
)
...
@@ -203,15 +217,6 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
...
@@ -203,15 +217,6 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
return
;
return
;
}
}
// Don't allow altitude to fall below 3 meters above home
double
currentAltRel
=
vehicle
->
altitudeRelative
()
->
rawValue
().
toDouble
();
if
(
altitudeChange
<=
0
&&
currentAltRel
<=
3
)
{
return
;
}
if
(
currentAltRel
+
altitudeChange
<
3
)
{
altitudeChange
=
3
-
currentAltRel
;
}
setGuidedMode
(
vehicle
,
true
);
setGuidedMode
(
vehicle
,
true
);
mavlink_message_t
msg
;
mavlink_message_t
msg
;
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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