Browse Source

AP_HAL_Linux: rename macros to avoid conflicts

these macros were also defined in NuttX in clock.h
mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
279c1b9d9c
  1. 2
      libraries/AP_HAL_Linux/Perf.cpp
  2. 4
      libraries/AP_HAL_Linux/PollerThread.cpp
  3. 4
      libraries/AP_HAL_Linux/RCOutput_AeroIO.cpp

2
libraries/AP_HAL_Linux/Perf.cpp

@ -41,7 +41,7 @@ static inline uint64_t now_nsec() @@ -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()

4
libraries/AP_HAL_Linux/PollerThread.cpp

@ -76,8 +76,8 @@ bool TimerPollable::adjust_timer(uint32_t timeout_usec) @@ -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;

4
libraries/AP_HAL_Linux/RCOutput_AeroIO.cpp

@ -276,12 +276,12 @@ uint16_t RCOutput_AeroIO::_usec_to_hw(uint16_t freq, uint16_t usec) @@ -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…
Cancel
Save