From 8101f2b5738c7c0bbb1e879755c70df1015c7002 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 31 Jan 2018 13:29:23 +1100 Subject: [PATCH] Rover: move sending of simstate up --- APMrover2/GCS_Mavlink.cpp | 13 ------------- APMrover2/Rover.h | 1 - 2 files changed, 14 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 0da0fb8785..719cef3406 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -152,14 +152,6 @@ void Rover::send_vfr_hud(mavlink_channel_t chan) 0); } -// report simulator state -void Rover::send_simstate(mavlink_channel_t chan) -{ -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - sitl.simstate_send(chan); -#endif -} - void Rover::send_rangefinder(mavlink_channel_t chan) { float distance_cm; @@ -297,11 +289,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) rover.send_vfr_hud(chan); break; - case MSG_SIMSTATE: - CHECK_PAYLOAD_SIZE(SIMSTATE); - rover.send_simstate(chan); - break; - case MSG_RANGEFINDER: CHECK_PAYLOAD_SIZE(RANGEFINDER); rover.send_rangefinder(chan); diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 4b3e75241d..c9ae399aa7 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -466,7 +466,6 @@ private: void send_nav_controller_output(mavlink_channel_t chan); void send_servo_out(mavlink_channel_t chan); void send_vfr_hud(mavlink_channel_t chan); - void send_simstate(mavlink_channel_t chan); void send_rangefinder(mavlink_channel_t chan); void send_pid_tuning(mavlink_channel_t chan); void send_wheel_encoder(mavlink_channel_t chan);