123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153 |
- #include "AP_VisualOdom.h"
- #include "AP_VisualOdom_Backend.h"
- #include "AP_VisualOdom_MAV.h"
- #include <AP_AHRS/AP_AHRS.h>
- #include <AP_Logger/AP_Logger.h>
- extern const AP_HAL::HAL &hal;
- const AP_Param::GroupInfo AP_VisualOdom::var_info[] = {
-
-
-
-
-
- AP_GROUPINFO("_TYPE", 0, AP_VisualOdom, _type, 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("_POS", 1, AP_VisualOdom, _pos_offset, 0.0f),
-
-
-
-
-
- AP_GROUPINFO("_ORIENT", 2, AP_VisualOdom, _orientation, ROTATION_NONE),
- AP_GROUPEND
- };
- 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;
- }
- void AP_VisualOdom::init()
- {
-
- if (_type == AP_VisualOdom_Type_MAV) {
- _driver = new AP_VisualOdom_MAV(*this);
- }
- }
- bool AP_VisualOdom::enabled() const
- {
- return ((_type != AP_VisualOdom_Type_None) && (_driver != nullptr));
- }
- void AP_VisualOdom::update()
- {
- if (!enabled()) {
- return;
- }
-
- if (_state.last_processed_sensor_update_ms == _state.last_sensor_update_ms) {
-
- return;
- }
- _state.last_processed_sensor_update_ms = _state.last_sensor_update_ms;
- const float time_delta_sec = get_time_delta_usec() / 1000000.0f;
- AP::ahrs_navekf().writeBodyFrameOdom(get_confidence(),
- get_position_delta(),
- get_angle_delta(),
- time_delta_sec,
- get_last_update_ms(),
- get_pos_offset());
-
- AP::logger().Write_VisualOdom(time_delta_sec,
- get_angle_delta(),
- get_position_delta(),
- get_confidence());
- }
- bool AP_VisualOdom::healthy() const
- {
- if (!enabled()) {
- return false;
- }
-
- return ((AP_HAL::millis() - _state.last_sensor_update_ms) < AP_VISUALODOM_TIMEOUT_MS);
- }
- void AP_VisualOdom::handle_msg(const mavlink_message_t &msg)
- {
-
- if (!enabled()) {
- return;
- }
-
- if (_driver != nullptr) {
- _driver->handle_msg(msg);
- }
- }
- AP_VisualOdom *AP_VisualOdom::_singleton;
- namespace AP {
- AP_VisualOdom *visualodom()
- {
- return AP_VisualOdom::get_singleton();
- }
- }
|