mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
APMrover2: compiler warnings: apply is_zero(float) or is_equal(float)
This commit is contained in:
parent
43006c0eec
commit
bff69de249
@ -337,7 +337,7 @@ struct PACKED log_Sonar {
|
|||||||
static void Log_Write_Sonar()
|
static void Log_Write_Sonar()
|
||||||
{
|
{
|
||||||
uint16_t turn_time = 0;
|
uint16_t turn_time = 0;
|
||||||
if (obstacle.turn_angle != 0) {
|
if (!AP_Math::is_zero(obstacle.turn_angle)) {
|
||||||
turn_time = hal.scheduler->millis() - obstacle.detected_time_ms;
|
turn_time = hal.scheduler->millis() - obstacle.detected_time_ms;
|
||||||
}
|
}
|
||||||
struct log_Sonar pkt = {
|
struct log_Sonar pkt = {
|
||||||
|
Loading…
Reference in New Issue
Block a user