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
60ee7a78
Commit
60ee7a78
authored
May 23, 2017
by
Don Gagne
Committed by
GitHub
May 23, 2017
Browse files
Merge pull request #5188 from DonLakeFlyer/HardenGuided
Better retries on arming, flight mode change and APM guided
parents
4423b2bf
d7bb6d85
Changes
5
Show whitespace changes
Inline
Side-by-side
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
60ee7a78
...
@@ -162,35 +162,42 @@ bool ArduCopterFirmwarePlugin::isCapable(const Vehicle* vehicle, FirmwareCapabil
...
@@ -162,35 +162,42 @@ bool ArduCopterFirmwarePlugin::isCapable(const Vehicle* vehicle, FirmwareCapabil
void
ArduCopterFirmwarePlugin
::
guidedModeRTL
(
Vehicle
*
vehicle
)
void
ArduCopterFirmwarePlugin
::
guidedModeRTL
(
Vehicle
*
vehicle
)
{
{
vehicle
->
setFlightMode
(
"RTL"
);
_
setFlightMode
AndValidate
(
vehicle
,
"RTL"
);
}
}
void
ArduCopterFirmwarePlugin
::
guidedModeLand
(
Vehicle
*
vehicle
)
void
ArduCopterFirmwarePlugin
::
guidedModeLand
(
Vehicle
*
vehicle
)
{
{
vehicle
->
setFlightMode
(
"Land"
);
_
setFlightMode
AndValidate
(
vehicle
,
"Land"
);
}
}
void
ArduCopterFirmwarePlugin
::
guidedModeTakeoff
(
Vehicle
*
vehicle
)
void
ArduCopterFirmwarePlugin
::
guidedModeTakeoff
(
Vehicle
*
vehicle
)
{
_guidedModeTakeoff
(
vehicle
);
}
bool
ArduCopterFirmwarePlugin
::
_guidedModeTakeoff
(
Vehicle
*
vehicle
)
{
{
QString
takeoffAltParam
(
"PILOT_TKOFF_ALT"
);
QString
takeoffAltParam
(
"PILOT_TKOFF_ALT"
);
if
(
!
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
))
{
float
takeoffAlt
=
0
;
qgcApp
()
->
showMessage
(
tr
(
"Unable to takeoff, %1 parameter missing."
).
arg
(
takeoffAltParam
));
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
))
{
return
;
}
Fact
*
takeoffAltFact
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
);
Fact
*
takeoffAltFact
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
);
float
takeoffAlt
=
takeoffAltFact
->
rawValue
().
toDouble
();
takeoffAlt
=
takeoffAltFact
->
rawValue
().
toDouble
();
}
if
(
takeoffAlt
<=
0
)
{
if
(
takeoffAlt
<=
0
)
{
takeoffAlt
=
2.5
;
takeoffAlt
=
2.5
;
}
else
{
}
else
{
takeoffAlt
/=
100
;
// centimeters -> meters
takeoffAlt
/=
100
;
// centimeters -> meters
}
}
setGuidedMode
(
vehicle
,
true
);
if
(
!
_setFlightModeAndValidate
(
vehicle
,
"Guided"
))
{
qgcApp
()
->
showMessage
(
tr
(
"Unable to takeoff: Vehicle failed to change to Guided mode."
));
return
false
;
}
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
false
;
}
}
vehicle
->
sendMavCommand
(
vehicle
->
defaultComponentId
(),
vehicle
->
sendMavCommand
(
vehicle
->
defaultComponentId
(),
...
@@ -198,6 +205,8 @@ void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle)
...
@@ -198,6 +205,8 @@ void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle)
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
,
takeoffAlt
);
takeoffAlt
);
return
true
;
}
}
void
ArduCopterFirmwarePlugin
::
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
)
void
ArduCopterFirmwarePlugin
::
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
)
...
@@ -246,13 +255,13 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
...
@@ -246,13 +255,13 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
void
ArduCopterFirmwarePlugin
::
pauseVehicle
(
Vehicle
*
vehicle
)
void
ArduCopterFirmwarePlugin
::
pauseVehicle
(
Vehicle
*
vehicle
)
{
{
vehicle
->
setFlightMode
(
"Brake"
);
_
setFlightMode
AndValidate
(
vehicle
,
"Brake"
);
}
}
void
ArduCopterFirmwarePlugin
::
setGuidedMode
(
Vehicle
*
vehicle
,
bool
guidedMode
)
void
ArduCopterFirmwarePlugin
::
setGuidedMode
(
Vehicle
*
vehicle
,
bool
guidedMode
)
{
{
if
(
guidedMode
)
{
if
(
guidedMode
)
{
vehicle
->
setFlightMode
(
"Guided"
);
_
setFlightMode
AndValidate
(
vehicle
,
"Guided"
);
}
else
{
}
else
{
pauseVehicle
(
vehicle
);
pauseVehicle
(
vehicle
);
}
}
...
@@ -293,11 +302,11 @@ void ArduCopterFirmwarePlugin::startMission(Vehicle* vehicle)
...
@@ -293,11 +302,11 @@ void ArduCopterFirmwarePlugin::startMission(Vehicle* vehicle)
double
currentAlt
=
vehicle
->
altitudeRelative
()
->
rawValue
().
toDouble
();
double
currentAlt
=
vehicle
->
altitudeRelative
()
->
rawValue
().
toDouble
();
if
(
!
vehicle
->
flying
())
{
if
(
!
vehicle
->
flying
())
{
guidedModeTakeoff
(
vehicle
)
;
if
(
_
guidedModeTakeoff
(
vehicle
)
)
{
// Wait for vehicle to get off ground before switching to auto
// Wait for vehicle to get off ground before switching to auto
(10 seconds)
bool
didTakeoff
=
false
;
bool
didTakeoff
=
false
;
for
(
int
i
=
0
;
i
<
5
0
;
i
++
)
{
for
(
int
i
=
0
;
i
<
10
0
;
i
++
)
{
if
(
vehicle
->
altitudeRelative
()
->
rawValue
().
toDouble
()
>=
currentAlt
+
1.0
)
{
if
(
vehicle
->
altitudeRelative
()
->
rawValue
().
toDouble
()
>=
currentAlt
+
1.0
)
{
didTakeoff
=
true
;
didTakeoff
=
true
;
break
;
break
;
...
@@ -307,11 +316,15 @@ void ArduCopterFirmwarePlugin::startMission(Vehicle* vehicle)
...
@@ -307,11 +316,15 @@ void ArduCopterFirmwarePlugin::startMission(Vehicle* vehicle)
}
}
if
(
!
didTakeoff
)
{
if
(
!
didTakeoff
)
{
qgcApp
()
->
showMessage
(
QStringLiteral
(
"Unable to s
witch to Auto
. Vehicle takeoff failed."
));
qgcApp
()
->
showMessage
(
QStringLiteral
(
"Unable to s
tart mission
. Vehicle takeoff failed."
));
return
;
return
;
}
}
}
}
}
vehicle
->
setFlightMode
(
missionFlightMode
());
if
(
!
_setFlightModeAndValidate
(
vehicle
,
missionFlightMode
()))
{
qgcApp
()
->
showMessage
(
QStringLiteral
(
"Unable to start mission. Vehicle failed to change to auto."
));
return
;
}
}
}
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
View file @
60ee7a78
...
@@ -81,6 +81,8 @@ public:
...
@@ -81,6 +81,8 @@ public:
private:
private:
static
bool
_remapParamNameIntialized
;
static
bool
_remapParamNameIntialized
;
static
FirmwarePlugin
::
remapParamNameMajorVersionMap_t
_remapParamName
;
static
FirmwarePlugin
::
remapParamNameMajorVersionMap_t
_remapParamName
;
bool
_guidedModeTakeoff
(
Vehicle
*
vehicle
);
};
};
#endif
#endif
src/FirmwarePlugin/FirmwarePlugin.cc
View file @
60ee7a78
...
@@ -437,21 +437,63 @@ bool FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle)
...
@@ -437,21 +437,63 @@ bool FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle)
bool
FirmwarePlugin
::
_armVehicleAndValidate
(
Vehicle
*
vehicle
)
bool
FirmwarePlugin
::
_armVehicleAndValidate
(
Vehicle
*
vehicle
)
{
{
if
(
!
vehicle
->
armed
())
{
if
(
vehicle
->
armed
())
{
vehicle
->
setArmed
(
true
)
;
return
true
;
}
}
// Wait for vehicle to return armed state for 2 seconds
bool
armedChanged
=
false
;
for
(
int
i
=
0
;
i
<
20
;
i
++
)
{
// We try arming 3 times
for
(
int
retries
=
0
;
retries
<
3
;
retries
++
)
{
vehicle
->
setArmed
(
true
);
// Wait for vehicle to return armed state for 3 seconds
for
(
int
i
=
0
;
i
<
30
;
i
++
)
{
if
(
vehicle
->
armed
())
{
if
(
vehicle
->
armed
())
{
armedChanged
=
true
;
break
;
}
QGC
::
SLEEP
::
msleep
(
100
);
qgcApp
()
->
processEvents
(
QEventLoop
::
ExcludeUserInputEvents
);
}
if
(
armedChanged
)
{
break
;
}
}
return
armedChanged
;
}
bool
FirmwarePlugin
::
_setFlightModeAndValidate
(
Vehicle
*
vehicle
,
const
QString
&
flightMode
)
{
if
(
vehicle
->
flightMode
()
==
flightMode
)
{
return
true
;
}
bool
flightModeChanged
=
false
;
// We try 3 times
for
(
int
retries
=
0
;
retries
<
3
;
retries
++
)
{
vehicle
->
setFlightMode
(
flightMode
);
// Wait for vehicle to return flight mode
for
(
int
i
=
0
;
i
<
30
;
i
++
)
{
if
(
vehicle
->
flightMode
()
==
flightMode
)
{
flightModeChanged
=
true
;
break
;
break
;
}
}
QGC
::
SLEEP
::
msleep
(
100
);
QGC
::
SLEEP
::
msleep
(
100
);
qgcApp
()
->
processEvents
(
QEventLoop
::
ExcludeUserInputEvents
);
qgcApp
()
->
processEvents
(
QEventLoop
::
ExcludeUserInputEvents
);
}
}
return
vehicle
->
armed
();
if
(
flightModeChanged
)
{
break
;
}
}
return
flightModeChanged
;
}
}
void
FirmwarePlugin
::
batteryConsumptionData
(
Vehicle
*
vehicle
,
int
&
mAhBattery
,
double
&
hoverAmps
,
double
&
cruiseAmps
)
const
void
FirmwarePlugin
::
batteryConsumptionData
(
Vehicle
*
vehicle
,
int
&
mAhBattery
,
double
&
hoverAmps
,
double
&
cruiseAmps
)
const
{
{
Q_UNUSED
(
vehicle
);
Q_UNUSED
(
vehicle
);
...
...
src/FirmwarePlugin/FirmwarePlugin.h
View file @
60ee7a78
...
@@ -296,10 +296,14 @@ public:
...
@@ -296,10 +296,14 @@ public:
static
const
char
*
px4FollowMeFlightMode
;
static
const
char
*
px4FollowMeFlightMode
;
protected:
protected:
// Arms the vehicle
,
w
a
it
ing for the arm state to change.
// Arms the vehicle wit
h validation and retries
// @return: true - vehicle armed, false - vehicle failed to arm
// @return: true - vehicle armed, false - vehicle failed to arm
bool
_armVehicleAndValidate
(
Vehicle
*
vehicle
);
bool
_armVehicleAndValidate
(
Vehicle
*
vehicle
);
// Sets the vehicle to the specified flight mode with validation and retries
// @return: true - vehicle in specified flight mode, false - flight mode change failed
bool
_setFlightModeAndValidate
(
Vehicle
*
vehicle
,
const
QString
&
flightMode
);
private:
private:
QVariantList
_toolBarIndicatorList
;
QVariantList
_toolBarIndicatorList
;
static
QVariantList
_cameraList
;
///< Standard QGC camera list
static
QVariantList
_cameraList
;
///< Standard QGC camera list
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
60ee7a78
...
@@ -331,12 +331,12 @@ void PX4FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
...
@@ -331,12 +331,12 @@ void PX4FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
void
PX4FirmwarePlugin
::
guidedModeRTL
(
Vehicle
*
vehicle
)
void
PX4FirmwarePlugin
::
guidedModeRTL
(
Vehicle
*
vehicle
)
{
{
vehicle
->
setFlightMode
(
_rtlFlightMode
);
_
setFlightMode
AndValidate
(
vehicle
,
_rtlFlightMode
);
}
}
void
PX4FirmwarePlugin
::
guidedModeLand
(
Vehicle
*
vehicle
)
void
PX4FirmwarePlugin
::
guidedModeLand
(
Vehicle
*
vehicle
)
{
{
vehicle
->
setFlightMode
(
_landingFlightMode
);
_
setFlightMode
AndValidate
(
vehicle
,
_landingFlightMode
);
}
}
void
PX4FirmwarePlugin
::
guidedModeOrbit
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
centerCoord
,
double
radius
,
double
velocity
,
double
altitude
)
void
PX4FirmwarePlugin
::
guidedModeOrbit
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
centerCoord
,
double
radius
,
double
velocity
,
double
altitude
)
...
@@ -457,13 +457,13 @@ void PX4FirmwarePlugin::startMission(Vehicle* vehicle)
...
@@ -457,13 +457,13 @@ void PX4FirmwarePlugin::startMission(Vehicle* vehicle)
return
;
return
;
}
}
vehicle
->
setFlightMode
(
missionFlightMode
());
_
setFlightMode
AndValidate
(
vehicle
,
missionFlightMode
());
}
}
void
PX4FirmwarePlugin
::
setGuidedMode
(
Vehicle
*
vehicle
,
bool
guidedMode
)
void
PX4FirmwarePlugin
::
setGuidedMode
(
Vehicle
*
vehicle
,
bool
guidedMode
)
{
{
if
(
guidedMode
)
{
if
(
guidedMode
)
{
vehicle
->
setFlightMode
(
_holdFlightMode
);
_
setFlightMode
AndValidate
(
vehicle
,
_holdFlightMode
);
}
else
{
}
else
{
pauseVehicle
(
vehicle
);
pauseVehicle
(
vehicle
);
}
}
...
...
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