mirror of https://github.com/ArduPilot/ardupilot
AP_VisualOdom: correct compilation when AP_AHRS_ENABLED is off
e.g. CubeOrange-periph-heavy
This commit is contained in:
parent
7b5a4d9f2c
commit
7e0ea05ae9
|
@ -56,6 +56,7 @@ void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_messa
|
||||||
|
|
||||||
// send to EKF
|
// send to EKF
|
||||||
const float time_delta_sec = packet.time_delta_usec * 1.0E-6;
|
const float time_delta_sec = packet.time_delta_usec * 1.0E-6;
|
||||||
|
#if AP_AHRS_ENABLED
|
||||||
AP::ahrs().writeBodyFrameOdom(packet.confidence,
|
AP::ahrs().writeBodyFrameOdom(packet.confidence,
|
||||||
position_delta,
|
position_delta,
|
||||||
angle_delta,
|
angle_delta,
|
||||||
|
@ -63,6 +64,7 @@ void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_messa
|
||||||
now_ms,
|
now_ms,
|
||||||
_frontend.get_delay_ms(),
|
_frontend.get_delay_ms(),
|
||||||
_frontend.get_pos_offset());
|
_frontend.get_pos_offset());
|
||||||
|
#endif
|
||||||
|
|
||||||
// log sensor data
|
// log sensor data
|
||||||
Write_VisualOdom(time_delta_sec,
|
Write_VisualOdom(time_delta_sec,
|
||||||
|
|
Loading…
Reference in New Issue