2017-03-01 07:17:45 -04:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "AP_VisualOdom_Backend.h"
|
|
|
|
|
2020-04-06 00:17:42 -03:00
|
|
|
#if HAL_VISUALODOM_ENABLED
|
|
|
|
|
2017-03-01 07:17:45 -04:00
|
|
|
class AP_VisualOdom_MAV : public AP_VisualOdom_Backend
|
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
// constructor
|
|
|
|
AP_VisualOdom_MAV(AP_VisualOdom &frontend);
|
|
|
|
|
2020-04-03 01:35:09 -03:00
|
|
|
// consume vision position estimate data and send to EKF. distances in meters
|
2020-04-10 01:36:26 -03:00
|
|
|
void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, uint8_t reset_counter) override;
|
2020-05-13 05:30:40 -03:00
|
|
|
|
|
|
|
// consume vision velocity estimate data and send to EKF, velocity in NED meters per second
|
|
|
|
void handle_vision_speed_estimate(uint64_t remote_time_us, uint32_t time_ms, const Vector3f &vel, uint8_t reset_counter) override;
|
2017-03-01 07:17:45 -04:00
|
|
|
};
|
2020-04-06 00:17:42 -03:00
|
|
|
|
|
|
|
#endif
|