|
|
@ -19,6 +19,7 @@ |
|
|
|
#include <AP_Param/AP_Param.h> |
|
|
|
#include <AP_Param/AP_Param.h> |
|
|
|
#include <AP_Math/AP_Math.h> |
|
|
|
#include <AP_Math/AP_Math.h> |
|
|
|
#include <AP_SerialManager/AP_SerialManager.h> |
|
|
|
#include <AP_SerialManager/AP_SerialManager.h> |
|
|
|
|
|
|
|
#include <GCS_MAVLink/GCS.h> |
|
|
|
|
|
|
|
|
|
|
|
class AP_VisualOdom_Backend; |
|
|
|
class AP_VisualOdom_Backend; |
|
|
|
|
|
|
|
|
|
|
@ -31,6 +32,11 @@ public: |
|
|
|
|
|
|
|
|
|
|
|
AP_VisualOdom(); |
|
|
|
AP_VisualOdom(); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// get singleton instance
|
|
|
|
|
|
|
|
static AP_VisualOdom *get_singleton() { |
|
|
|
|
|
|
|
return _singleton; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// external position backend types (used by _TYPE parameter)
|
|
|
|
// external position backend types (used by _TYPE parameter)
|
|
|
|
enum AP_VisualOdom_Type { |
|
|
|
enum AP_VisualOdom_Type { |
|
|
|
AP_VisualOdom_Type_None = 0, |
|
|
|
AP_VisualOdom_Type_None = 0, |
|
|
@ -72,6 +78,8 @@ public: |
|
|
|
|
|
|
|
|
|
|
|
private: |
|
|
|
private: |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
static AP_VisualOdom *_singleton; |
|
|
|
|
|
|
|
|
|
|
|
// parameters
|
|
|
|
// parameters
|
|
|
|
AP_Int8 _type; |
|
|
|
AP_Int8 _type; |
|
|
|
AP_Vector3f _pos_offset; // position offset of the camera in the body frame
|
|
|
|
AP_Vector3f _pos_offset; // position offset of the camera in the body frame
|
|
|
@ -83,3 +91,7 @@ private: |
|
|
|
// state of backend
|
|
|
|
// state of backend
|
|
|
|
VisualOdomState _state; |
|
|
|
VisualOdomState _state; |
|
|
|
}; |
|
|
|
}; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
namespace AP { |
|
|
|
|
|
|
|
AP_VisualOdom *visualodom(); |
|
|
|
|
|
|
|
}; |
|
|
|