2 This program is free software: you can redistribute it and/or modify
3 it under the terms of the GNU General Public License as published by
4 the Free Software Foundation, either version 3 of the License, or
5 (at your option) any later version.
7 This program is distributed in the hope that it will be useful,
8 but WITHOUT ANY WARRANTY; without even the implied warranty of
9 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10 GNU General Public License for more details.
12 You should have received a copy of the GNU General Public License
13 along with this program. If not, see <http://www.gnu.org/licenses/>.
17 #include "AP_VisualOdom.h"
19 #if HAL_VISUALODOM_ENABLED
21 #include <AP_Logger/AP_Logger_config.h>
23 class AP_VisualOdom_Backend
26 // constructor. This incorporates initialisation as well.
27 AP_VisualOdom_Backend(AP_VisualOdom
&frontend
);
29 // return true if sensor is basically healthy (we are receiving data)
32 // return quality as a measure from -1 ~ 100
33 // -1 means failed, 0 means unknown, 1 is worst, 100 is best
34 int8_t quality() const { return _quality
; }
37 // consume vision_position_delta mavlink messages
38 void handle_vision_position_delta_msg(const mavlink_message_t
&msg
);
41 // consume vision pose estimate data and send to EKF. distances in meters
42 // quality of -1 means failed, 0 means unknown, 1 is worst, 100 is best
43 virtual void handle_pose_estimate(uint64_t remote_time_us
, uint32_t time_ms
, float x
, float y
, float z
, const Quaternion
&attitude
, float posErr
, float angErr
, uint8_t reset_counter
, int8_t quality
) = 0;
45 // consume vision velocity estimate data and send to EKF, velocity in NED meters per second
46 // quality of -1 means failed, 0 means unknown, 1 is worst, 100 is best
47 virtual void handle_vision_speed_estimate(uint64_t remote_time_us
, uint32_t time_ms
, const Vector3f
&vel
, uint8_t reset_counter
, int8_t quality
) = 0;
49 // request sensor's yaw be aligned with vehicle's AHRS/EKF attitude
50 virtual void request_align_yaw_to_ahrs() {}
52 // handle request to align position with AHRS
53 virtual void align_position_to_ahrs(bool align_xy
, bool align_z
) {}
55 // arming check - by default no checks performed
56 virtual bool pre_arm_check(char *failure_msg
, uint8_t failure_msg_len
) const { return true; }
60 // returns the system time of the last reset if reset_counter has not changed
61 // updates the reset timestamp to the current system time if the reset_counter has changed
62 uint32_t get_reset_timestamp_ms(uint8_t reset_counter
);
64 AP_VisualOdom::VisualOdom_Type
get_type(void) const {
65 return _frontend
.get_type();
68 #if HAL_LOGGING_ENABLED
70 void Write_VisualOdom(float time_delta
, const Vector3f
&angle_delta
, const Vector3f
&position_delta
, float confidence
);
71 void Write_VisualPosition(uint64_t remote_time_us
, uint32_t time_ms
, float x
, float y
, float z
, float roll
, float pitch
, float yaw
, float pos_err
, float ang_err
, uint8_t reset_counter
, bool ignored
, int8_t quality
);
72 void Write_VisualVelocity(uint64_t remote_time_us
, uint32_t time_ms
, const Vector3f
&vel
, uint8_t reset_counter
, bool ignored
, int8_t quality
);
75 AP_VisualOdom
&_frontend
; // reference to frontend
76 uint32_t _last_update_ms
; // system time of last update from sensor (used by health checks)
78 // reset counter handling
79 uint8_t _last_reset_counter
; // last sensor reset counter received
80 uint32_t _reset_timestamp_ms
; // time reset counter was received
83 int8_t _quality
; // last recorded quality
86 #endif // HAL_VISUALODOM_ENABLED