123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101 |
- #pragma once
- #include <AP_Common/AP_Common.h>
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Param/AP_Param.h>
- #include <GCS_MAVLink/GCS.h>
- class AP_VisualOdom_Backend;
- #define AP_VISUALODOM_TIMEOUT_MS 300
- class AP_VisualOdom
- {
- public:
- friend class AP_VisualOdom_Backend;
- AP_VisualOdom();
-
- static AP_VisualOdom *get_singleton() {
- return _singleton;
- }
-
- enum AP_VisualOdom_Type {
- AP_VisualOdom_Type_None = 0,
- AP_VisualOdom_Type_MAV = 1
- };
-
- struct VisualOdomState {
- Vector3f angle_delta;
- Vector3f position_delta;
- uint64_t time_delta_usec;
- float confidence;
- uint32_t last_sensor_update_ms;
- uint32_t last_processed_sensor_update_ms;
- };
-
- void init();
-
-
- void update();
-
- bool enabled() const;
-
- bool healthy() const;
-
- const Vector3f &get_pos_offset(void) const { return _pos_offset; }
-
- void handle_msg(const mavlink_message_t &msg);
- static const struct AP_Param::GroupInfo var_info[];
- private:
- static AP_VisualOdom *_singleton;
-
- const Vector3f &get_angle_delta() const { return _state.angle_delta; }
- const Vector3f &get_position_delta() const { return _state.position_delta; }
- uint64_t get_time_delta_usec() const { return _state.time_delta_usec; }
- float get_confidence() const { return _state.confidence; }
- uint32_t get_last_update_ms() const { return _state.last_sensor_update_ms; }
-
- AP_Int8 _type;
- AP_Vector3f _pos_offset;
- AP_Int8 _orientation;
-
- AP_VisualOdom_Backend *_driver;
-
- VisualOdomState _state;
- };
- namespace AP {
- AP_VisualOdom *visualodom();
- };
|