mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduSub: remove AC_TERRAIN compilation option
Use AP_TERRAIN_AVAILABLE instead
This commit is contained in:
parent
3684741517
commit
ed0b0451cf
@ -226,7 +226,7 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
||||
break;
|
||||
|
||||
case MSG_TERRAIN:
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);
|
||||
sub.terrain.send_request(chan);
|
||||
#endif
|
||||
@ -361,7 +361,7 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
||||
MSG_SYSTEM_TIME,
|
||||
MSG_RANGEFINDER,
|
||||
MSG_DISTANCE_SENSOR,
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
MSG_TERRAIN,
|
||||
#endif
|
||||
MSG_BATTERY2,
|
||||
@ -709,7 +709,7 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg)
|
||||
|
||||
case MAVLINK_MSG_ID_TERRAIN_DATA:
|
||||
case MAVLINK_MSG_ID_TERRAIN_CHECK:
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
sub.terrain.handle_data(chan, msg);
|
||||
#endif
|
||||
break;
|
||||
@ -761,7 +761,7 @@ uint64_t GCS_MAVLINK_Sub::capabilities() const
|
||||
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |
|
||||
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
|
||||
MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION |
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
(sub.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) |
|
||||
#endif
|
||||
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
|
||||
|
@ -67,7 +67,7 @@ void GCS_Sub::update_vehicle_sensor_status_flags()
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
switch (sub.terrain.status()) {
|
||||
case AP_Terrain::TerrainStatusDisabled:
|
||||
break;
|
||||
|
@ -27,7 +27,7 @@ void Sub::Log_Write_Control_Tuning()
|
||||
{
|
||||
// get terrain altitude
|
||||
float terr_alt = 0.0f;
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
terrain.height_above_terrain(terr_alt, true);
|
||||
#endif
|
||||
|
||||
|
@ -593,7 +593,7 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
GOBJECT(rangefinder, "RNGFND", RangeFinder),
|
||||
#endif
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
// @Group: TERRAIN_
|
||||
// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp
|
||||
GOBJECT(terrain, "TERRAIN_", AP_Terrain),
|
||||
|
@ -372,7 +372,7 @@ private:
|
||||
#endif
|
||||
|
||||
// terrain handling
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
AP_Terrain terrain{mission};
|
||||
#endif
|
||||
|
||||
|
@ -244,7 +244,3 @@
|
||||
#ifndef AC_RALLY
|
||||
#define AC_RALLY DISABLED
|
||||
#endif
|
||||
|
||||
#ifndef AC_TERRAIN
|
||||
#define AC_TERRAIN DISABLED // Requires Rally enabled as well
|
||||
#endif
|
||||
|
@ -84,7 +84,7 @@ void Sub::init_ardupilot()
|
||||
AP::compass().init();
|
||||
|
||||
// init Location class
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
Location::set_terrain(&terrain);
|
||||
wp_nav.set_terrain(&terrain);
|
||||
#endif
|
||||
|
@ -3,7 +3,7 @@
|
||||
// update terrain data
|
||||
void Sub::terrain_update()
|
||||
{
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
terrain.update();
|
||||
|
||||
// tell the rangefinder our height, so it can go into power saving
|
||||
@ -20,7 +20,7 @@ void Sub::terrain_update()
|
||||
// log terrain data - should be called at 1hz
|
||||
void Sub::terrain_logging()
|
||||
{
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
if (should_log(MASK_LOG_GPS)) {
|
||||
terrain.log_terrain_data();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user