mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_Linux: rename macros to avoid conflicts
these macros were also defined in NuttX in clock.h
This commit is contained in:
parent
3687b6bdf0
commit
279c1b9d9c
@ -41,7 +41,7 @@ static inline uint64_t now_nsec()
|
||||
{
|
||||
struct timespec ts;
|
||||
clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
return ts.tv_nsec + (ts.tv_sec * NSEC_PER_SEC);
|
||||
return ts.tv_nsec + (ts.tv_sec * AP_NSEC_PER_SEC);
|
||||
}
|
||||
|
||||
Perf *Perf::get_instance()
|
||||
|
@ -76,8 +76,8 @@ bool TimerPollable::adjust_timer(uint32_t timeout_usec)
|
||||
|
||||
struct itimerspec spec = { };
|
||||
|
||||
spec.it_interval.tv_nsec = timeout_usec * NSEC_PER_USEC;
|
||||
spec.it_value.tv_nsec = timeout_usec * NSEC_PER_USEC;
|
||||
spec.it_interval.tv_nsec = timeout_usec * AP_NSEC_PER_USEC;
|
||||
spec.it_value.tv_nsec = timeout_usec * AP_NSEC_PER_USEC;
|
||||
|
||||
if (timerfd_settime(_fd, 0, &spec, nullptr) < 0) {
|
||||
return false;
|
||||
|
@ -276,12 +276,12 @@ uint16_t RCOutput_AeroIO::_usec_to_hw(uint16_t freq, uint16_t usec)
|
||||
{
|
||||
float f = freq;
|
||||
float u = usec;
|
||||
return 0xFFFF * u * f / USEC_PER_SEC;
|
||||
return 0xFFFF * u * f / AP_USEC_PER_SEC;
|
||||
}
|
||||
|
||||
uint16_t RCOutput_AeroIO::_hw_to_usec(uint16_t freq, uint16_t hw_val)
|
||||
{
|
||||
float p = hw_val;
|
||||
float f = freq;
|
||||
return p * USEC_PER_SEC / (0xFFFF * f);
|
||||
return p * AP_USEC_PER_SEC / (0xFFFF * f);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user