mirror of https://github.com/ArduPilot/ardupilot
AP_DDS: move closing #endif for status publisher
- Must be before the status_ok check. Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
This commit is contained in:
parent
d1674b089a
commit
e14045898d
|
@ -1615,10 +1615,11 @@ void AP_DDS_Client::update()
|
||||||
}
|
}
|
||||||
last_status_check_time_ms = cur_time_ms;
|
last_status_check_time_ms = cur_time_ms;
|
||||||
}
|
}
|
||||||
|
#endif // AP_DDS_STATUS_PUB_ENABLED
|
||||||
|
|
||||||
status_ok = uxr_run_session_time(&session, 1);
|
status_ok = uxr_run_session_time(&session, 1);
|
||||||
}
|
}
|
||||||
#endif // AP_DDS_STATUS_PUB_ENABLED
|
|
||||||
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||||
extern "C" {
|
extern "C" {
|
||||||
int clock_gettime(clockid_t clockid, struct timespec *ts);
|
int clock_gettime(clockid_t clockid, struct timespec *ts);
|
||||||
|
|
Loading…
Reference in New Issue