AP_DAL: VisualOdom request_align_yaw_to_ahrs

This commit is contained in:
Randy Mackay 2024-03-27 14:43:30 +09:00
parent 8a6880711a
commit 440fb8b03b
2 changed files with 12 additions and 0 deletions

View File

@ -8,6 +8,15 @@
#include "AP_DAL.h"
#include <AP_Vehicle/AP_Vehicle_Type.h>
// request sensor's yaw be aligned with vehicle's AHRS/EKF attitude
void AP_DAL_VisualOdom::request_align_yaw_to_ahrs()
{
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone)
auto *vo = AP::visualodom();
vo->request_align_yaw_to_ahrs();
#endif
}
/*
update position offsets to align to AHRS position
should only be called when this library is not being used as the position source

View File

@ -27,6 +27,9 @@ public:
return RVOH.pos_offset;
}
// request sensor's yaw be aligned with vehicle's AHRS/EKF attitude
void request_align_yaw_to_ahrs();
// update position offsets to align to AHRS position
// should only be called when this library is not being used as the position source
void align_position_to_ahrs(bool align_xy, bool align_z);