From 398d07a68a3b23c4cc656082c956aa0c7e69f516 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 27 Nov 2017 17:16:41 +1100 Subject: [PATCH] Copter: tighten return types of mavlink functions and variables --- ArduCopter/Copter.h | 2 +- ArduCopter/GCS_Mavlink.cpp | 2 +- ArduCopter/motor_test.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 45cf7bd606..a64ab0f6af 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -1021,7 +1021,7 @@ private: void update_notify(); void motor_test_output(); bool mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc); - uint8_t mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value, float timeout_sec, uint8_t motor_count); + MAV_RESULT mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value, float timeout_sec, uint8_t motor_count); void motor_test_stop(); void arm_motors_check(); void auto_disarm_check(); diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index c3e20a3738..1d84008eee 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -720,7 +720,7 @@ void GCS_MAVLINK_Copter::send_banner() void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) { - uint8_t result = MAV_RESULT_FAILED; // assume failure. Each messages id is responsible for return ACK or NAK if required + MAV_RESULT result = MAV_RESULT_FAILED; // assume failure. Each messages id is responsible for return ACK or NAK if required switch (msg->msgid) { diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index 7467fd4680..378e83069c 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -121,7 +121,7 @@ bool Copter::mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc) // mavlink_motor_test_start - start motor test - spin a single motor at a specified pwm // returns MAV_RESULT_ACCEPTED on success, MAV_RESULT_FAILED on failure -uint8_t Copter::mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value, +MAV_RESULT Copter::mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value, float timeout_sec, uint8_t motor_count) { if (motor_count == 0) {