From fb5532356ae7b9c62cfd7b24b249b5af767c8264 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 2 Mar 2019 09:38:21 +1100 Subject: [PATCH] Rover: move sending of RPM message up --- APMrover2/GCS_Mavlink.cpp | 18 ------------------ APMrover2/Rover.h | 1 - 2 files changed, 19 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index d8cfb44b93..6c3b987627 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -155,19 +155,6 @@ void GCS_MAVLINK_Rover::send_rangefinder() const voltage); } -/* - send RPM packet - */ -void Rover::send_rpm(mavlink_channel_t chan) -{ - if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) { - mavlink_msg_rpm_send( - chan, - rpm_sensor.get_rpm(0), - rpm_sensor.get_rpm(1)); - } -} - /* send PID tuning message */ @@ -323,11 +310,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) rover.send_servo_out(chan); break; - case MSG_RPM: - CHECK_PAYLOAD_SIZE(RPM); - rover.send_rpm(chan); - break; - case MSG_WHEEL_DISTANCE: CHECK_PAYLOAD_SIZE(WHEEL_DISTANCE); rover.send_wheel_encoder_distance(chan); diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 90df492e12..e2638f9099 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -436,7 +436,6 @@ private: // GCS_Mavlink.cpp void send_servo_out(mavlink_channel_t chan); - void send_rpm(mavlink_channel_t chan); void send_wheel_encoder_distance(mavlink_channel_t chan); // Log.cpp