mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: resolve send_text compiler warnings
This commit is contained in:
parent
480a3ebb03
commit
a5c76b614e
@ -68,7 +68,7 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, bool on)
|
|||||||
control_mode != &mode_rtl &&
|
control_mode != &mode_rtl &&
|
||||||
control_mode != &mode_hold) {
|
control_mode != &mode_hold) {
|
||||||
failsafe.triggered = failsafe.bits;
|
failsafe.triggered = failsafe.bits;
|
||||||
gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe trigger 0x%x", static_cast<uint32_t>(failsafe.triggered));
|
gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe trigger 0x%x", (unsigned int)failsafe.triggered);
|
||||||
|
|
||||||
// clear rc overrides
|
// clear rc overrides
|
||||||
RC_Channels::clear_overrides();
|
RC_Channels::clear_overrides();
|
||||||
|
@ -583,13 +583,13 @@ bool ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||||||
if (loiter_duration > 0) {
|
if (loiter_duration > 0) {
|
||||||
// send message including loiter time
|
// send message including loiter time
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%u. Loiter for %u seconds",
|
gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%u. Loiter for %u seconds",
|
||||||
static_cast<uint32_t>(cmd.index),
|
(unsigned int)cmd.index,
|
||||||
static_cast<uint32_t>(loiter_duration));
|
(unsigned int)loiter_duration);
|
||||||
// record the current time i.e. start timer
|
// record the current time i.e. start timer
|
||||||
loiter_start_time = millis();
|
loiter_start_time = millis();
|
||||||
} else {
|
} else {
|
||||||
// send simpler message to GCS
|
// send simpler message to GCS
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%u", static_cast<uint32_t>(cmd.index));
|
gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%u", (unsigned int)cmd.index);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -150,7 +150,7 @@ void Rover::read_rangefinders(void)
|
|||||||
}
|
}
|
||||||
if (obstacle.detected_count == g.rangefinder_debounce) {
|
if (obstacle.detected_count == g.rangefinder_debounce) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder1 obstacle %u cm",
|
gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder1 obstacle %u cm",
|
||||||
static_cast<uint32_t>(obstacle.rangefinder1_distance_cm));
|
(unsigned int)obstacle.rangefinder1_distance_cm);
|
||||||
}
|
}
|
||||||
obstacle.detected_time_ms = AP_HAL::millis();
|
obstacle.detected_time_ms = AP_HAL::millis();
|
||||||
obstacle.turn_angle = g.rangefinder_turn_angle;
|
obstacle.turn_angle = g.rangefinder_turn_angle;
|
||||||
@ -161,7 +161,7 @@ void Rover::read_rangefinders(void)
|
|||||||
}
|
}
|
||||||
if (obstacle.detected_count == g.rangefinder_debounce) {
|
if (obstacle.detected_count == g.rangefinder_debounce) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder2 obstacle %u cm",
|
gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder2 obstacle %u cm",
|
||||||
static_cast<uint32_t>(obstacle.rangefinder2_distance_cm));
|
(unsigned int)obstacle.rangefinder2_distance_cm);
|
||||||
}
|
}
|
||||||
obstacle.detected_time_ms = AP_HAL::millis();
|
obstacle.detected_time_ms = AP_HAL::millis();
|
||||||
obstacle.turn_angle = -g.rangefinder_turn_angle;
|
obstacle.turn_angle = -g.rangefinder_turn_angle;
|
||||||
@ -177,7 +177,7 @@ void Rover::read_rangefinders(void)
|
|||||||
}
|
}
|
||||||
if (obstacle.detected_count == g.rangefinder_debounce) {
|
if (obstacle.detected_count == g.rangefinder_debounce) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder obstacle %u cm",
|
gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder obstacle %u cm",
|
||||||
static_cast<uint32_t>(obstacle.rangefinder1_distance_cm));
|
(unsigned int)obstacle.rangefinder1_distance_cm);
|
||||||
}
|
}
|
||||||
obstacle.detected_time_ms = AP_HAL::millis();
|
obstacle.detected_time_ms = AP_HAL::millis();
|
||||||
obstacle.turn_angle = g.rangefinder_turn_angle;
|
obstacle.turn_angle = g.rangefinder_turn_angle;
|
||||||
|
Loading…
Reference in New Issue
Block a user