diff --git a/Tools/autotest/test_build_options.py b/Tools/autotest/test_build_options.py index a11b8c63b169a..7cbc005c310aa 100755 --- a/Tools/autotest/test_build_options.py +++ b/Tools/autotest/test_build_options.py @@ -258,7 +258,6 @@ def define_is_whitelisted_for_feature_in_code(self, target, define): 'AP_COMPASS_MAG3110_ENABLED', # must be in hwdef, not probed 'AP_COMPASS_MMC5XX3_ENABLED', # must be in hwdef, not probed 'AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', # completely elided - 'AP_MAVLINK_MSG_HIL_GPS_ENABLED', # no symbol available 'AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', # no symbol available 'AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', # no symbol available 'HAL_MSP_SENSORS_ENABLED', # no symbol available diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 54be58a3bd074..f31edfaf87ff3 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -364,7 +364,6 @@ def config_option(self): Feature('MAVLink', 'MAVLINK_VERSION_REQUEST', 'AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', 'Enable Old AUTOPILOT_VERSION_REQUEST mesage', 0, None), # noqa Feature('MAVLink', 'REQUEST_AUTOPILOT_CAPA', 'AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', 'Enable Old REQUEST_AUTOPILOT_CAPABILITIES command', 0, None), # noqa Feature('MAVLink', 'MAV_MSG_RELAY_STATUS', 'AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', 'Enable Send RELAY_STATUS message', 0, 'RELAY'), # noqa - Feature('MAVLink', 'MAV_MSG_HIL_GPS', 'AP_MAVLINK_MSG_HIL_GPS_ENABLED', 'Enable Receive HIL_GPS messages', 0, 'MAV'), # noqa Feature('MAVLink', 'MAV_MSG_MOUNT_CONTROL', 'AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED', 'Enable Deprecated MOUNT_CONTROL message', 0, "MOUNT"), # noqa Feature('MAVLink', 'MAV_MSG_MOUNT_CONFIGURE', 'AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED', 'Enable Deprecated MOUNT_CONFIGURE message', 0, "MOUNT"), # noqa Feature('MAVLink', 'AP_MAVLINK_BATTERY2_ENABLED', 'AP_MAVLINK_BATTERY2_ENABLED', 'Enable Send old BATTERY2 message', 0, None), # noqa diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 36a375522aa05..de6eec6589523 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -273,7 +273,6 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_CUSTOMROTATIONS_ENABLED', 'AP_CustomRotations::init'), ('AP_OSD_LINK_STATS_EXTENSIONS_ENABLED', r'AP_OSD_Screen::draw_rc_tx_power'), ('HAL_ENABLE_DRONECAN_DRIVERS', r'AP_DroneCAN::init'), - ('AP_MAVLINK_MSG_HIL_GPS_ENABLED', r'mavlink_msg_hil_gps_decode'), ('AP_BARO_PROBE_EXTERNAL_I2C_BUSES', r'AP_Baro::_probe_i2c_barometers'), ('AP_RSSI_ENABLED', r'AP_RSSI::init'), diff --git a/libraries/AP_GPS/AP_GPS_MAV.cpp b/libraries/AP_GPS/AP_GPS_MAV.cpp index b9100f5f17c46..2a059af35b018 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.cpp +++ b/libraries/AP_GPS/AP_GPS_MAV.cpp @@ -143,51 +143,8 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t &msg) state.last_gps_time_ms = now_ms; _new_data = true; break; - } - -#if AP_MAVLINK_MSG_HIL_GPS_ENABLED - case MAVLINK_MSG_ID_HIL_GPS: { - mavlink_hil_gps_t packet; - mavlink_msg_hil_gps_decode(&msg, &packet); - - // check if target instance belongs to incoming gps data. - if (state.instance != packet.id) { - return; - } - - state.time_week = 0; - state.time_week_ms = packet.time_usec/1000; - state.status = (AP_GPS::GPS_Status)packet.fix_type; + } - Location loc = {}; - loc.lat = packet.lat; - loc.lng = packet.lon; - loc.alt = packet.alt * 0.1f; - state.location = loc; - state.hdop = MIN(packet.eph, GPS_UNKNOWN_DOP); - state.vdop = MIN(packet.epv, GPS_UNKNOWN_DOP); - if (packet.vel < 65535) { - state.ground_speed = packet.vel * 0.01f; - } - Vector3f vel(packet.vn*0.01f, packet.ve*0.01f, packet.vd*0.01f); - state.velocity = vel; - if (packet.vd != 0) { - state.have_vertical_velocity = true; - } - if (packet.cog < 36000) { - state.ground_course = packet.cog * 0.01f; - } - state.have_speed_accuracy = false; - state.have_horizontal_accuracy = false; - state.have_vertical_accuracy = false; - if (packet.satellites_visible < 255) { - state.num_sats = packet.satellites_visible; - } - state.last_gps_time_ms = AP_HAL::millis(); - _new_data = true; - break; - } -#endif // AP_MAVLINK_MSG_HIL_GPS_ENABLED default: // ignore all other messages break; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 9a1528b9dca4e..f44417ba896b6 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4299,11 +4299,6 @@ void GCS_MAVLINK::handle_message(const mavlink_message_t &msg) #endif #if AP_GPS_ENABLED -#if AP_MAVLINK_MSG_HIL_GPS_ENABLED - case MAVLINK_MSG_ID_HIL_GPS: - send_received_message_deprecation_warning("HIL_GPS"); - FALLTHROUGH; -#endif case MAVLINK_MSG_ID_GPS_RTCM_DATA: case MAVLINK_MSG_ID_GPS_INPUT: case MAVLINK_MSG_ID_GPS_INJECT_DATA: diff --git a/libraries/GCS_MAVLink/GCS_config.h b/libraries/GCS_MAVLink/GCS_config.h index 5f059cb9a1042..2c8800a959c25 100644 --- a/libraries/GCS_MAVLink/GCS_config.h +++ b/libraries/GCS_MAVLink/GCS_config.h @@ -71,15 +71,6 @@ #define AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED HAL_GCS_ENABLED && HAL_RALLY_ENABLED #endif -// CODE_REMOVAL -// handling of HIL_GPS is slated to be removed in 4.7; GPS_INPUT can be used -// in its place -// ArduPilot 4.6 stops compiling support in -// ArduPilot 4.7 removes the code entirely -#ifndef AP_MAVLINK_MSG_HIL_GPS_ENABLED -#define AP_MAVLINK_MSG_HIL_GPS_ENABLED 0 -#endif - // CODE_REMOVAL // ArduPilot 4.5 sends deprecation warnings for MOUNT_CONTROL/MOUNT_CONFIGURE // ArduPilot 4.6 stops compiling them in