From 81e9edd80afc57ad76c0fbc753b7c9cdabfe5d16 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 2 Jan 2018 09:21:21 +1100 Subject: [PATCH] Copter: move sending of sim state up --- ArduCopter/Copter.h | 1 - ArduCopter/GCS_Mavlink.cpp | 17 ----------------- 2 files changed, 18 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 01f3ebd19b..d222d4f8ec 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -761,7 +761,6 @@ private: void send_fence_status(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); void send_rpm(mavlink_channel_t chan); void send_pid_tuning(mavlink_channel_t chan); diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index d650568466..4c90f5fad8 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -171,14 +171,6 @@ void NOINLINE Copter::send_nav_controller_output(mavlink_channel_t chan) 0); } -// report simulator state -void NOINLINE Copter::send_simstate(mavlink_channel_t chan) -{ -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - sitl.simstate_send(chan); -#endif -} - void NOINLINE Copter::send_vfr_hud(mavlink_channel_t chan) { mavlink_msg_vfr_hud_send( @@ -342,15 +334,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) #endif break; - case MSG_SIMSTATE: -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - CHECK_PAYLOAD_SIZE(SIMSTATE); - copter.send_simstate(chan); -#endif - CHECK_PAYLOAD_SIZE(AHRS2); - send_ahrs2(); - break; - case MSG_MOUNT_STATUS: #if MOUNT == ENABLED CHECK_PAYLOAD_SIZE(MOUNT_STATUS);