SITL: Added comment to clarify IMU acceleration value
[ardupilot.git] / libraries / AP_VisualOdom / AP_VisualOdom_MAV.h
blobc1d1c131dc4ff4bdeea7442f7e5763e03d894e8f
1 #pragma once
3 #include "AP_VisualOdom_config.h"
5 #if AP_VISUALODOM_MAV_ENABLED
7 #include "AP_VisualOdom_Backend.h"
9 class AP_VisualOdom_MAV : public AP_VisualOdom_Backend
12 public:
13 // constructor
14 using AP_VisualOdom_Backend::AP_VisualOdom_Backend;
16 // consume vision pose estimate data and send to EKF. distances in meters
17 // quality of -1 means failed, 0 means unknown, 1 is worst, 100 is best
18 void handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter, int8_t quality) override;
20 // consume vision velocity estimate data and send to EKF, velocity in NED meters per second
21 // quality of -1 means failed, 0 means unknown, 1 is worst, 100 is best
22 void handle_vision_speed_estimate(uint64_t remote_time_us, uint32_t time_ms, const Vector3f &vel, uint8_t reset_counter, int8_t quality) override;
25 #endif // AP_VISUALODOM_MAV_ENABLED