AP_VisualOdom: create singleton

This commit is contained in:
Peter Barker 2018-04-06 18:05:14 +10:00 committed by Peter Barker
parent 31f796f0c5
commit 1a5a1dac8c
2 changed files with 29 additions and 0 deletions

View File

@ -61,6 +61,12 @@ const AP_Param::GroupInfo AP_VisualOdom::var_info[] = {
AP_VisualOdom::AP_VisualOdom()
{
AP_Param::setup_object_defaults(this, var_info);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (_singleton != nullptr) {
AP_HAL::panic("VisualOdom must be singleton");
}
#endif
_singleton = this;
}
// detect and initialise any sensors
@ -103,3 +109,14 @@ void AP_VisualOdom::handle_msg(mavlink_message_t *msg)
}
}
// singleton instance
AP_VisualOdom *AP_VisualOdom::_singleton;
namespace AP {
AP_VisualOdom *visualodom()
{
return AP_VisualOdom::get_singleton();
}
}

View File

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