Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_NavEKF3: dereference arrays using remembered allocation count #26335

Merged
merged 2 commits into from
Feb 28, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,8 @@ void NavEKF3_core::Log_Write_Beacon(uint64_t time_us)
}

// Ensure that beacons are not skipped due to calling this function at a rate lower than the updates
if (rngBcn.fuseDataReportIndex >= rngBcn.N) {
if (rngBcn.fuseDataReportIndex >= rngBcn.N ||
rngBcn.fuseDataReportIndex > rngBcn.numFusionReports) {
rngBcn.fuseDataReportIndex = 0;
}

Expand Down
16 changes: 11 additions & 5 deletions libraries/AP_NavEKF3/AP_NavEKF3_RngBcnFusion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,15 @@ void NavEKF3_core::BeaconFusion::InitialiseVariables()
posOffsetMinVar = 0.0f;
minOffsetStateChangeFilt = 0.0f;
fuseDataReportIndex = 0;
if (AP::dal().beacon()) {
if (fusionReport == nullptr) {
fusionReport = new BeaconFusion::FusionReport[AP::dal().beacon()->count()];
delete[] fusionReport;
fusionReport = nullptr;
numFusionReports = 0;
auto *beacon = AP::dal().beacon();
if (beacon != nullptr) {
const uint8_t count = beacon->count();
fusionReport = new BeaconFusion::FusionReport[count];
if (fusionReport != nullptr) {
numFusionReports = count;
}
}
posOffsetNED.zero();
Expand Down Expand Up @@ -310,7 +316,7 @@ void NavEKF3_core::FuseRngBcn()
}

// Update the fusion report
if (rngBcn.fusionReport && rngBcn.dataDelayed.beacon_ID < dal.beacon()->count()) {
if (rngBcn.dataDelayed.beacon_ID < rngBcn.numFusionReports) {
auto &report = rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID];
report.beaconPosNED = rngBcn.dataDelayed.beacon_posNED;
report.innov = rngBcn.innov;
Expand Down Expand Up @@ -549,7 +555,7 @@ void NavEKF3_core::FuseRngBcnStatic()
rngBcn.alignmentCompleted = true;
}
// Update the fusion report
if (rngBcn.fusionReport && rngBcn.dataDelayed.beacon_ID < dal.beacon()->count()) {
if (rngBcn.dataDelayed.beacon_ID < rngBcn.numFusionReports) {
auto &report = rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID];
report.beaconPosNED = rngBcn.dataDelayed.beacon_posNED;
report.innov = rngBcn.innov;
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_core.h
Original file line number Diff line number Diff line change
Expand Up @@ -1372,6 +1372,7 @@ class NavEKF3_core : public NavEKF_core_common
ftype testRatio; // innovation consistency test ratio
Vector3F beaconPosNED; // beacon NED position
} *fusionReport;
uint8_t numFusionReports;
} rngBcn;
#endif // if EK3_FEATURE_BEACON_FUSION

Expand Down
Loading