#pragma once #include "AP_VisualOdom_Backend.h" #if HAL_VISUALODOM_ENABLED class AP_VisualOdom_MAV : public AP_VisualOdom_Backend { public: // constructor AP_VisualOdom_MAV(AP_VisualOdom &frontend); // consume vision_position_delta mavlink messages void handle_vision_position_delta_msg(const mavlink_message_t &msg) override; // consume vision position estimate data and send to EKF. distances in meters void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude) override; }; #endif