AP_HAL: simplify the processing of milliseconds from the time

This commit is contained in:
murata 2016-10-14 22:12:31 +09:00 committed by Randy Mackay
parent 5a9276a5c4
commit ba60cce0c1

View File

@ -89,13 +89,16 @@ uint32_t AP_HAL::Util::get_time_utc(int32_t hour, int32_t min, int32_t sec, int3
{
// determine highest value specified (0=none, 1=ms, 2=sec, 3=min, 4=hour)
int8_t largest_element = 0;
if (ms != -1) largest_element = 1;
if (sec != -1) largest_element = 2;
if (min != -1) largest_element = 3;
if (hour != -1) largest_element = 4;
// exit immediately if no time specified
if (largest_element == 0) {
if (hour != -1) {
largest_element = 4;
} else if (min != -1) {
largest_element = 3;
} else if (sec != -1) {
largest_element = 2;
} else if (ms != -1) {
largest_element = 1;
} else {
// exit immediately if no time specified
return 0;
}
@ -109,7 +112,7 @@ uint32_t AP_HAL::Util::get_time_utc(int32_t hour, int32_t min, int32_t sec, int3
total_delay_ms += ms - curr_ms;
}
if (largest_element == 1 && total_delay_ms < 0) {
total_delay_ms += 1000;
return static_cast<uint32_t>(total_delay_ms += 1000);
}
// calculate sec to target
@ -117,7 +120,7 @@ uint32_t AP_HAL::Util::get_time_utc(int32_t hour, int32_t min, int32_t sec, int3
total_delay_ms += (sec - curr_sec)*1000;
}
if (largest_element == 2 && total_delay_ms < 0) {
total_delay_ms += (60*1000);
return static_cast<uint32_t>(total_delay_ms += (60*1000));
}
// calculate min to target
@ -125,7 +128,7 @@ uint32_t AP_HAL::Util::get_time_utc(int32_t hour, int32_t min, int32_t sec, int3
total_delay_ms += (min - curr_min)*60*1000;
}
if (largest_element == 3 && total_delay_ms < 0) {
total_delay_ms += (60*60*1000);
return static_cast<uint32_t>(total_delay_ms += (60*60*1000));
}
// calculate hours to target
@ -133,9 +136,9 @@ uint32_t AP_HAL::Util::get_time_utc(int32_t hour, int32_t min, int32_t sec, int3
total_delay_ms += (hour - curr_hour)*60*60*1000;
}
if (largest_element == 4 && total_delay_ms < 0) {
total_delay_ms += (24*60*60*1000);
return static_cast<uint32_t>(total_delay_ms += (24*60*60*1000));
}
// total delay in milliseconds
return (uint32_t)total_delay_ms;
return static_cast<uint32_t>(total_delay_ms);
}