Skip to content

Commit

Permalink
AP_DAL: VisualOdom request_align_yaw_to_ahrs
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Nov 20, 2024
1 parent 8a68807 commit 440fb8b
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 0 deletions.
9 changes: 9 additions & 0 deletions libraries/AP_DAL/AP_DAL_VisualOdom.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_DAL/AP_DAL_VisualOdom.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,9 @@ class AP_DAL_VisualOdom {
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);
Expand Down

0 comments on commit 440fb8b

Please sign in to comment.