mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Hott_Telem: allow for compilation without AP_RTC_ENABLED
This commit is contained in:
parent
53f4709a78
commit
f90093b628
@ -289,12 +289,14 @@ void AP_Hott_Telem::send_GPS(void)
|
|||||||
|
|
||||||
msg.home_direction = degrees(atan2f(home_vec.y, home_vec.x)) * 0.5 + 0.5;
|
msg.home_direction = degrees(atan2f(home_vec.y, home_vec.x)) * 0.5 + 0.5;
|
||||||
|
|
||||||
|
#if AP_RTC_ENABLED
|
||||||
AP_RTC &rtc = AP::rtc();
|
AP_RTC &rtc = AP::rtc();
|
||||||
{
|
{
|
||||||
WITH_SEMAPHORE(rtc.get_semaphore());
|
WITH_SEMAPHORE(rtc.get_semaphore());
|
||||||
uint16_t ms;
|
uint16_t ms;
|
||||||
rtc.get_system_clock_utc(msg.gps_time_h, msg.gps_time_m, msg.gps_time_s, ms);
|
rtc.get_system_clock_utc(msg.gps_time_h, msg.gps_time_m, msg.gps_time_s, ms);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
send_packet((const uint8_t *)&msg, sizeof(msg));
|
send_packet((const uint8_t *)&msg, sizeof(msg));
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user