Path: blob/master/libraries/AP_DAL/AP_DAL_VisualOdom.h
9649 views
#pragma once12#include <AP_Logger/LogStructure.h>34#include <AP_VisualOdom/AP_VisualOdom.h>56#if HAL_VISUALODOM_ENABLED78class AP_DAL_VisualOdom {9public:1011// return VisualOdom health12bool healthy() const {13return RVOH.healthy;14}1516bool enabled() const {17return RVOH.enabled;18}1920uint16_t get_delay_ms() const {21return RVOH.delay_ms;22}2324// return a 3D vector defining the position offset of the camera in meters relative to the body frame origin25const Vector3f &get_pos_offset() const {26return RVOH.pos_offset;27}2829// update position offsets to align to AHRS position30// should only be called when this library is not being used as the position source31void align_position_to_ahrs(bool align_xy, bool align_z);3233void start_frame();3435void handle_message(const log_RVOH &msg) {36RVOH = msg;37}3839private:4041struct log_RVOH RVOH;42};4344#endif // HAL_VISUALODOM_ENABLED454647