diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index e1df00bc44..cdd03e55f8 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -251,14 +251,6 @@ void NOINLINE Sub::send_nav_controller_output(mavlink_channel_t chan) 0); } -// report simulator state -void NOINLINE Sub::send_simstate(mavlink_channel_t chan) -{ -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - sitl.simstate_send(chan); -#endif -} - void NOINLINE Sub::send_vfr_hud(mavlink_channel_t chan) { mavlink_msg_vfr_hud_send( @@ -461,15 +453,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) #endif break; - case MSG_SIMSTATE: -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - CHECK_PAYLOAD_SIZE(SIMSTATE); - sub.send_simstate(chan); -#endif - CHECK_PAYLOAD_SIZE(AHRS2); - send_ahrs2(); - break; - case MSG_MOUNT_STATUS: #if MOUNT == ENABLED CHECK_PAYLOAD_SIZE(MOUNT_STATUS); diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 1d897a91de..a721db8cbe 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -476,7 +476,6 @@ private: void send_heartbeat(mavlink_channel_t chan); void send_extended_status1(mavlink_channel_t chan); void send_nav_controller_output(mavlink_channel_t chan); - void send_simstate(mavlink_channel_t chan); void send_vfr_hud(mavlink_channel_t chan); #if RPM_ENABLED == ENABLED void send_rpm(mavlink_channel_t chan);