From a5c76b614e262fa4ca0c7f3cd4f481e50590a057 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 29 Jul 2019 15:35:10 +0900 Subject: [PATCH] Rover: resolve send_text compiler warnings --- APMrover2/failsafe.cpp | 2 +- APMrover2/mode_auto.cpp | 6 +++--- APMrover2/sensors.cpp | 6 +++--- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/APMrover2/failsafe.cpp b/APMrover2/failsafe.cpp index 2bf237d935..748e46a8fc 100644 --- a/APMrover2/failsafe.cpp +++ b/APMrover2/failsafe.cpp @@ -68,7 +68,7 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, bool on) control_mode != &mode_rtl && control_mode != &mode_hold) { failsafe.triggered = failsafe.bits; - gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe trigger 0x%x", static_cast(failsafe.triggered)); + gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe trigger 0x%x", (unsigned int)failsafe.triggered); // clear rc overrides RC_Channels::clear_overrides(); diff --git a/APMrover2/mode_auto.cpp b/APMrover2/mode_auto.cpp index 2cb157665a..ded181b3fe 100644 --- a/APMrover2/mode_auto.cpp +++ b/APMrover2/mode_auto.cpp @@ -583,13 +583,13 @@ bool ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd) if (loiter_duration > 0) { // send message including loiter time gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%u. Loiter for %u seconds", - static_cast(cmd.index), - static_cast(loiter_duration)); + (unsigned int)cmd.index, + (unsigned int)loiter_duration); // record the current time i.e. start timer loiter_start_time = millis(); } else { // send simpler message to GCS - gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%u", static_cast(cmd.index)); + gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%u", (unsigned int)cmd.index); } } diff --git a/APMrover2/sensors.cpp b/APMrover2/sensors.cpp index 717ef5ee45..4372700a08 100644 --- a/APMrover2/sensors.cpp +++ b/APMrover2/sensors.cpp @@ -150,7 +150,7 @@ void Rover::read_rangefinders(void) } if (obstacle.detected_count == g.rangefinder_debounce) { gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder1 obstacle %u cm", - static_cast(obstacle.rangefinder1_distance_cm)); + (unsigned int)obstacle.rangefinder1_distance_cm); } obstacle.detected_time_ms = AP_HAL::millis(); obstacle.turn_angle = g.rangefinder_turn_angle; @@ -161,7 +161,7 @@ void Rover::read_rangefinders(void) } if (obstacle.detected_count == g.rangefinder_debounce) { gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder2 obstacle %u cm", - static_cast(obstacle.rangefinder2_distance_cm)); + (unsigned int)obstacle.rangefinder2_distance_cm); } obstacle.detected_time_ms = AP_HAL::millis(); obstacle.turn_angle = -g.rangefinder_turn_angle; @@ -177,7 +177,7 @@ void Rover::read_rangefinders(void) } if (obstacle.detected_count == g.rangefinder_debounce) { gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder obstacle %u cm", - static_cast(obstacle.rangefinder1_distance_cm)); + (unsigned int)obstacle.rangefinder1_distance_cm); } obstacle.detected_time_ms = AP_HAL::millis(); obstacle.turn_angle = g.rangefinder_turn_angle;