Fix for preprocessing condition in SemanticLidar
This commit is contained in:
parent
d3935f6824
commit
ea194c462e
|
@ -138,7 +138,7 @@ void ARayCastSemanticLidar::PreprocessRays(uint32_t Channels, uint32_t MaxPoints
|
|||
|
||||
for (auto& conds : RayPreprocessCondition) {
|
||||
conds.clear();
|
||||
conds.reserve(MaxPointsPerChannel);
|
||||
conds.resize(MaxPointsPerChannel);
|
||||
std::fill(conds.begin(), conds.end(), true);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue