mirror of https://github.com/ArduPilot/ardupilot
Copter: fix build for lack of AC_TERRAIN define
This commit is contained in:
parent
8234fd4c39
commit
5f039ba06d
|
@ -1079,7 +1079,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
AP_GROUPINFO("GUID_TIMEOUT", 46, ParametersG2, guided_timeout, 3.0),
|
||||
#endif
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
// @Param: TERRAIN_MARGIN
|
||||
// @DisplayName: Terrain following altitude margin
|
||||
// @Description: Terrain following altitude margin. Vehicle will stop if distance from target altitude is larger than this margin (in meters)
|
||||
|
|
|
@ -653,7 +653,7 @@ public:
|
|||
AP_Float guided_timeout;
|
||||
#endif
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
AP_Float terrain_margin;
|
||||
#endif
|
||||
};
|
||||
|
|
|
@ -30,7 +30,7 @@ void Copter::terrain_logging()
|
|||
// return terrain following altitude margin. Vehicle will stop if distance from target altitude is larger than this margin (in meters)
|
||||
float Copter::get_terrain_margin() const
|
||||
{
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
return MAX(g2.terrain_margin.get(), 0.1);
|
||||
#else
|
||||
return 10;
|
||||
|
|
Loading…
Reference in New Issue