mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
Copter: CTUN logging checks return value of height_above_terrain
This resolves a Covarity warning but it was actually safe before No functional change
This commit is contained in:
parent
542677f1d5
commit
575795fa84
@ -319,7 +319,9 @@ void Copter::Log_Write_Control_Tuning()
|
|||||||
// get terrain altitude
|
// get terrain altitude
|
||||||
float terr_alt = 0.0f;
|
float terr_alt = 0.0f;
|
||||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
terrain.height_above_terrain(terr_alt, true);
|
if (terrain.height_above_terrain(terr_alt, true)) {
|
||||||
|
terr_alt = 0.0f;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
struct log_Control_Tuning pkt = {
|
struct log_Control_Tuning pkt = {
|
||||||
|
Loading…
Reference in New Issue
Block a user