Plane: replace HAVE_AP_TERRAIN with AP_TERRAIN_AVAILABLE

This commit is contained in:
Andrew Tridgell 2014-07-25 07:58:39 +10:00
parent 3faafc9644
commit b158b7e5a9
5 changed files with 18 additions and 18 deletions

View File

@ -467,7 +467,7 @@ AP_Airspeed airspeed(aparm);
////////////////////////////////////////////////////////////////////////////////
// terrain handling
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
AP_Terrain terrain(ahrs);
#endif
@ -665,7 +665,7 @@ static struct {
// centimeters. Used for glide slope handling
int32_t offset_cm;
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
// are we trying to follow terrain?
bool terrain_following;
@ -993,7 +993,7 @@ static void one_second_loop()
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
AP_Notify::flags.armed = arming.is_armed() || arming.arming_required() == AP_Arming::NO;
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
terrain.update();
#endif
}

View File

@ -243,7 +243,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
battery_current = battery.current_amps() * 100;
}
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
switch (terrain.status()) {
case AP_Terrain::TerrainStatusDisabled:
break;
@ -631,7 +631,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
break;
case MSG_TERRAIN:
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);
terrain.send_request(chan);
#endif
@ -870,7 +870,7 @@ GCS_MAVLINK::data_stream_send(void)
send_message(MSG_WIND);
send_message(MSG_RANGEFINDER);
send_message(MSG_SYSTEM_TIME);
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
send_message(MSG_TERRAIN);
#endif
}
@ -1490,7 +1490,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_TERRAIN_DATA:
case MAVLINK_MSG_ID_TERRAIN_CHECK:
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
terrain.handle_data(chan, msg);
#endif
break;

View File

@ -445,7 +445,7 @@ public:
AP_Int8 level_roll_limit;
AP_Int8 flapin_channel;
AP_Int8 flaperon_output;
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
AP_Int8 terrain_follow;
#endif

View File

@ -356,7 +356,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Standard
GSCALAR(flybywire_elev_reverse, "FBWB_ELEV_REV", 0),
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
// @Param: TERRAIN_FOLLOW
// @DisplayName: Use terrain following
// @Description: This enables terrain following for CRUISE mode, FBWB mode and RTL. To use this option you also need to set TERRAIN_ENABLE to 1, which enables terrain data fetching from the GCS, and you need to have a GCS that supports sending terrain data to the aircraft. When terrain following is enabled then CRUISE and FBWB mode will hold height above terrain rather than height above home. In RTL the return to launch altitude will be considered to be a height above the terrain.
@ -876,7 +876,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Path: ../libraries/AP_RangeFinder/RangeFinder.cpp
GOBJECT(sonar, "RNGFND", RangeFinder),
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
// @Group: TERRAIN
// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp
GOBJECT(terrain, "TERRAIN_", AP_Terrain),

View File

@ -134,7 +134,7 @@ static void set_target_altitude_current(void)
// reset any glide slope offset
reset_offset_altitude();
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
// also record the terrain altitude if possible
float terrain_altitude;
if (g.terrain_follow && terrain.height_above_terrain(current_loc, terrain_altitude)) {
@ -169,7 +169,7 @@ static void set_target_altitude_location(const Location &loc)
if (loc.flags.relative_alt) {
target_altitude.amsl_cm += home.alt;
}
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
/*
if this location has the terrain_alt flag set and we know the
terrain altitude of our current location then treat it as a
@ -195,7 +195,7 @@ static void set_target_altitude_location(const Location &loc)
*/
static int32_t relative_target_altitude_cm(void)
{
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
float relative_home_height;
if (target_altitude.terrain_following &&
terrain.height_relative_home_equivalent(current_loc,
@ -216,7 +216,7 @@ static int32_t relative_target_altitude_cm(void)
static void change_target_altitude(int32_t change_cm)
{
target_altitude.amsl_cm += change_cm;
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
if (target_altitude.terrain_following) {
target_altitude.terrain_alt_cm += change_cm;
}
@ -259,7 +259,7 @@ static void constrain_target_altitude_location(const Location &loc1, const Locat
*/
static int32_t calc_altitude_error_cm(void)
{
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
float terrain_height;
if (target_altitude.terrain_following &&
terrain.height_above_terrain(current_loc, terrain_height)) {
@ -278,7 +278,7 @@ static void check_minimum_altitude(void)
return;
}
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
if (target_altitude.terrain_following) {
// set our target terrain height to be at least the min set
if (target_altitude.terrain_alt_cm < g.FBWB_min_altitude_cm) {
@ -311,7 +311,7 @@ static void set_offset_altitude_location(const Location &loc)
{
target_altitude.offset_cm = loc.alt - current_loc.alt;
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
float terrain_altitude_loc, terrain_altitude_current;
if (loc.flags.terrain_alt &&
terrain.height_amsl(current_loc, terrain_altitude_current) &&
@ -336,7 +336,7 @@ static void set_offset_altitude_location(const Location &loc)
*/
static bool above_location_current(const Location &loc)
{
#if HAVE_AP_TERRAIN
#if AP_TERRAIN_AVAILABLE
float terrain_alt;
if (loc.flags.terrain_alt &&
terrain.height_above_terrain(current_loc, terrain_alt)) {