diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index a58dd90967..81e0210b62 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -245,14 +245,6 @@ float GCS_MAVLINK_Plane::vfr_hud_climbrate() const return AP::baro().get_climb_rate(); } -// report simulator state -void GCS_MAVLINK_Plane::send_simstate() const -{ -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - GCS_MAVLINK::send_simstate(); -#endif -} - void GCS_MAVLINK_Plane::send_wind() const { const Vector3f wind = AP::ahrs().wind_estimate(); @@ -1409,4 +1401,4 @@ int8_t GCS_MAVLINK_Plane::high_latency_air_temperature() const } return air_temperature; } -#endif // HAL_HIGH_LATENCY2_ENABLED \ No newline at end of file +#endif // HAL_HIGH_LATENCY2_ENABLED diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index 53236a537b..8f0c1e4426 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -29,7 +29,6 @@ protected: void send_aoa_ssa(); void send_attitude() const override; - void send_simstate() const override; void send_wind() const; bool persist_streamrates() const override { return true; }