mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 23:18:29 -04:00
AP_VisualOdom: support error estimates with quaternion
This commit is contained in:
parent
20dd667fdc
commit
8654ea886d
@ -191,7 +191,7 @@ void AP_VisualOdom::handle_vision_position_estimate(uint64_t remote_time_us, uin
|
|||||||
}
|
}
|
||||||
|
|
||||||
// general purpose method to consume position estimate data and send to EKF
|
// general purpose method to consume position estimate data and send to EKF
|
||||||
void AP_VisualOdom::handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, uint8_t reset_counter)
|
void AP_VisualOdom::handle_vision_position_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)
|
||||||
{
|
{
|
||||||
// exit immediately if not enabled
|
// exit immediately if not enabled
|
||||||
if (!enabled()) {
|
if (!enabled()) {
|
||||||
@ -200,7 +200,7 @@ void AP_VisualOdom::handle_vision_position_estimate(uint64_t remote_time_us, uin
|
|||||||
|
|
||||||
// call backend
|
// call backend
|
||||||
if (_driver != nullptr) {
|
if (_driver != nullptr) {
|
||||||
_driver->handle_vision_position_estimate(remote_time_us, time_ms, x, y, z, attitude, 0, 0, reset_counter);
|
_driver->handle_vision_position_estimate(remote_time_us, time_ms, x, y, z, attitude, posErr, angErr, reset_counter);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -88,7 +88,7 @@ public:
|
|||||||
// general purpose methods to consume position estimate data and send to EKF
|
// general purpose methods to consume position estimate data and send to EKF
|
||||||
// distances in meters, roll, pitch and yaw are in radians
|
// distances in meters, roll, pitch and yaw are in radians
|
||||||
void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw, float posErr, float angErr, uint8_t reset_counter);
|
void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw, float posErr, float angErr, uint8_t reset_counter);
|
||||||
void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, uint8_t reset_counter);
|
void handle_vision_position_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);
|
||||||
|
|
||||||
// general purpose methods to consume velocity estimate data and send to EKF
|
// general purpose methods to consume velocity estimate data and send to EKF
|
||||||
// velocity in NED meters per second
|
// velocity in NED meters per second
|
||||||
|
Loading…
Reference in New Issue
Block a user