mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_VisualOdom: correct unused variable in visualodom
when both logging and gcs are compiled out
This commit is contained in:
parent
ef044e39e9
commit
f55c35487b
@ -55,7 +55,9 @@ void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_messa
|
|||||||
_last_update_ms = now_ms;
|
_last_update_ms = now_ms;
|
||||||
|
|
||||||
// send to EKF
|
// send to EKF
|
||||||
|
#if AP_AHRS_ENABLED || HAL_LOGGING_ENABLED
|
||||||
const float time_delta_sec = packet.time_delta_usec * 1.0E-6;
|
const float time_delta_sec = packet.time_delta_usec * 1.0E-6;
|
||||||
|
#endif
|
||||||
#if AP_AHRS_ENABLED
|
#if AP_AHRS_ENABLED
|
||||||
AP::ahrs().writeBodyFrameOdom(packet.confidence,
|
AP::ahrs().writeBodyFrameOdom(packet.confidence,
|
||||||
position_delta,
|
position_delta,
|
||||||
|
Loading…
Reference in New Issue
Block a user