Avoid auto for Eigen expressions. (#899)
While harmless in most cases, auto can delay evaluation of expressions in unexpected ways. So it is better to avoid auto for Eigen expressions. https://eigen.tuxfamily.org/dox/TopicPitfalls.htmlmaster
parent
2a74484be1
commit
7448f93b50
|
@ -229,7 +229,7 @@ LocalTrajectoryBuilder::InsertIntoSubmap(
|
||||||
}
|
}
|
||||||
active_submaps_.InsertRangeData(filtered_range_data_in_local,
|
active_submaps_.InsertRangeData(filtered_range_data_in_local,
|
||||||
gravity_alignment);
|
gravity_alignment);
|
||||||
const auto rotational_scan_matcher_histogram =
|
const Eigen::VectorXf rotational_scan_matcher_histogram =
|
||||||
scan_matching::RotationalScanMatcher::ComputeHistogram(
|
scan_matching::RotationalScanMatcher::ComputeHistogram(
|
||||||
sensor::TransformPointCloud(
|
sensor::TransformPointCloud(
|
||||||
filtered_range_data_in_tracking.returns,
|
filtered_range_data_in_tracking.returns,
|
||||||
|
|
|
@ -94,7 +94,7 @@ void OutlierRemovingPointsProcessor::ProcessInPhaseTwo(
|
||||||
const Eigen::Vector3f delta = batch.points[i] - batch.origin;
|
const Eigen::Vector3f delta = batch.points[i] - batch.origin;
|
||||||
const float length = delta.norm();
|
const float length = delta.norm();
|
||||||
for (float x = 0; x < length; x += voxel_size_) {
|
for (float x = 0; x < length; x += voxel_size_) {
|
||||||
const auto index =
|
const Eigen::Array3i index =
|
||||||
voxels_.GetCellIndex(batch.origin + (x / length) * delta);
|
voxels_.GetCellIndex(batch.origin + (x / length) * delta);
|
||||||
if (voxels_.value(index).hits > 0) {
|
if (voxels_.value(index).hits > 0) {
|
||||||
++voxels_.mutable_value(index)->rays;
|
++voxels_.mutable_value(index)->rays;
|
||||||
|
@ -108,7 +108,8 @@ void OutlierRemovingPointsProcessor::ProcessInPhaseThree(
|
||||||
constexpr double kMissPerHitLimit = 3;
|
constexpr double kMissPerHitLimit = 3;
|
||||||
std::unordered_set<int> to_remove;
|
std::unordered_set<int> to_remove;
|
||||||
for (size_t i = 0; i < batch->points.size(); ++i) {
|
for (size_t i = 0; i < batch->points.size(); ++i) {
|
||||||
const auto voxel = voxels_.value(voxels_.GetCellIndex(batch->points[i]));
|
const VoxelData voxel =
|
||||||
|
voxels_.value(voxels_.GetCellIndex(batch->points[i]));
|
||||||
if (!(voxel.rays < kMissPerHitLimit * voxel.hits)) {
|
if (!(voxel.rays < kMissPerHitLimit * voxel.hits)) {
|
||||||
to_remove.insert(i);
|
to_remove.insert(i);
|
||||||
}
|
}
|
||||||
|
|
|
@ -134,9 +134,9 @@ std::unique_ptr<Image> DrawProbabilityGrid(
|
||||||
}
|
}
|
||||||
auto image = common::make_unique<Image>(cell_limits.num_x_cells,
|
auto image = common::make_unique<Image>(cell_limits.num_x_cells,
|
||||||
cell_limits.num_y_cells);
|
cell_limits.num_y_cells);
|
||||||
for (const auto& xy_index :
|
for (const Eigen::Array2i& xy_index :
|
||||||
cartographer::mapping_2d::XYIndexRangeIterator(cell_limits)) {
|
cartographer::mapping_2d::XYIndexRangeIterator(cell_limits)) {
|
||||||
const auto index = xy_index + *offset;
|
const Eigen::Array2i index = xy_index + *offset;
|
||||||
constexpr uint8 kUnknownValue = 128;
|
constexpr uint8 kUnknownValue = 128;
|
||||||
const uint8 value =
|
const uint8 value =
|
||||||
probability_grid.IsKnown(index)
|
probability_grid.IsKnown(index)
|
||||||
|
|
|
@ -149,7 +149,8 @@ void XRayPointsProcessor::WriteVoxels(const Aggregation& aggregation,
|
||||||
}
|
}
|
||||||
|
|
||||||
// Returns the (x, y) pixel of the given 'index'.
|
// Returns the (x, y) pixel of the given 'index'.
|
||||||
const auto voxel_index_to_pixel = [this](const Eigen::Array3i& index) {
|
const auto voxel_index_to_pixel =
|
||||||
|
[this](const Eigen::Array3i& index) -> Eigen::Array2i {
|
||||||
// We flip the y axis, since matrices rows are counted from the top.
|
// We flip the y axis, since matrices rows are counted from the top.
|
||||||
return Eigen::Array2i(bounding_box_.max()[1] - index[1],
|
return Eigen::Array2i(bounding_box_.max()[1] - index[1],
|
||||||
bounding_box_.max()[2] - index[2]);
|
bounding_box_.max()[2] - index[2]);
|
||||||
|
|
|
@ -37,7 +37,7 @@ class CeresScanMatcherTest : public ::testing::Test {
|
||||||
: hybrid_grid_(1.f),
|
: hybrid_grid_(1.f),
|
||||||
expected_pose_(
|
expected_pose_(
|
||||||
transform::Rigid3d::Translation(Eigen::Vector3d(-1., 0., 0.))) {
|
transform::Rigid3d::Translation(Eigen::Vector3d(-1., 0., 0.))) {
|
||||||
for (const auto& point :
|
for (const Eigen::Vector3f& point :
|
||||||
{Eigen::Vector3f(-3.f, 2.f, 0.f), Eigen::Vector3f(-4.f, 2.f, 0.f),
|
{Eigen::Vector3f(-3.f, 2.f, 0.f), Eigen::Vector3f(-4.f, 2.f, 0.f),
|
||||||
Eigen::Vector3f(-5.f, 2.f, 0.f), Eigen::Vector3f(-6.f, 2.f, 0.f),
|
Eigen::Vector3f(-5.f, 2.f, 0.f), Eigen::Vector3f(-6.f, 2.f, 0.f),
|
||||||
Eigen::Vector3f(-6.f, 3.f, 1.f), Eigen::Vector3f(-6.f, 4.f, 2.f),
|
Eigen::Vector3f(-6.f, 3.f, 1.f), Eigen::Vector3f(-6.f, 4.f, 2.f),
|
||||||
|
|
|
@ -29,7 +29,7 @@ class InterpolatedGridTest : public ::testing::Test {
|
||||||
protected:
|
protected:
|
||||||
InterpolatedGridTest()
|
InterpolatedGridTest()
|
||||||
: hybrid_grid_(0.1f), interpolated_grid_(hybrid_grid_) {
|
: hybrid_grid_(0.1f), interpolated_grid_(hybrid_grid_) {
|
||||||
for (const auto& point :
|
for (const Eigen::Vector3f& point :
|
||||||
{Eigen::Vector3f(-3.f, 2.f, 0.f), Eigen::Vector3f(-4.f, 2.f, 0.f),
|
{Eigen::Vector3f(-3.f, 2.f, 0.f), Eigen::Vector3f(-4.f, 2.f, 0.f),
|
||||||
Eigen::Vector3f(-5.f, 2.f, 0.f), Eigen::Vector3f(-6.f, 2.f, 0.f),
|
Eigen::Vector3f(-5.f, 2.f, 0.f), Eigen::Vector3f(-6.f, 2.f, 0.f),
|
||||||
Eigen::Vector3f(-6.f, 3.f, 1.f), Eigen::Vector3f(-6.f, 4.f, 2.f),
|
Eigen::Vector3f(-6.f, 3.f, 1.f), Eigen::Vector3f(-6.f, 4.f, 2.f),
|
||||||
|
|
|
@ -24,7 +24,8 @@ std::function<float(const transform::Rigid3f&)> CreateLowResolutionMatcher(
|
||||||
const HybridGrid* low_resolution_grid, const sensor::PointCloud* points) {
|
const HybridGrid* low_resolution_grid, const sensor::PointCloud* points) {
|
||||||
return [=](const transform::Rigid3f& pose) {
|
return [=](const transform::Rigid3f& pose) {
|
||||||
float score = 0.f;
|
float score = 0.f;
|
||||||
for (const auto& point : sensor::TransformPointCloud(*points, pose)) {
|
for (const Eigen::Vector3f& point :
|
||||||
|
sensor::TransformPointCloud(*points, pose)) {
|
||||||
// TODO(zhengj, whess): Interpolate the Grid to get better score.
|
// TODO(zhengj, whess): Interpolate the Grid to get better score.
|
||||||
score += low_resolution_grid->GetProbability(
|
score += low_resolution_grid->GetProbability(
|
||||||
low_resolution_grid->GetCellIndex(point));
|
low_resolution_grid->GetCellIndex(point));
|
||||||
|
|
|
@ -39,7 +39,7 @@ class RealTimeCorrelativeScanMatcherTest : public ::testing::Test {
|
||||||
: hybrid_grid_(0.1f),
|
: hybrid_grid_(0.1f),
|
||||||
expected_pose_(Eigen::Vector3d(-1., 0., 0.),
|
expected_pose_(Eigen::Vector3d(-1., 0., 0.),
|
||||||
Eigen::Quaterniond::Identity()) {
|
Eigen::Quaterniond::Identity()) {
|
||||||
for (const auto& point :
|
for (const Eigen::Vector3f& point :
|
||||||
{Eigen::Vector3f(-3.f, 2.f, 0.f), Eigen::Vector3f(-4.f, 2.f, 0.f),
|
{Eigen::Vector3f(-3.f, 2.f, 0.f), Eigen::Vector3f(-4.f, 2.f, 0.f),
|
||||||
Eigen::Vector3f(-5.f, 2.f, 0.f), Eigen::Vector3f(-6.f, 2.f, 0.f),
|
Eigen::Vector3f(-5.f, 2.f, 0.f), Eigen::Vector3f(-6.f, 2.f, 0.f),
|
||||||
Eigen::Vector3f(-6.f, 3.f, 1.f), Eigen::Vector3f(-6.f, 4.f, 2.f),
|
Eigen::Vector3f(-6.f, 3.f, 1.f), Eigen::Vector3f(-6.f, 4.f, 2.f),
|
||||||
|
|
|
@ -106,7 +106,7 @@ TEST(CompressPointCloudTest, CompressesNoGaps) {
|
||||||
EXPECT_EQ(decompressed.size(), recompressed.size());
|
EXPECT_EQ(decompressed.size(), recompressed.size());
|
||||||
|
|
||||||
std::vector<float> x_coord;
|
std::vector<float> x_coord;
|
||||||
for (const auto& p : compressed) {
|
for (const Eigen::Vector3f& p : compressed) {
|
||||||
x_coord.push_back(p[0]);
|
x_coord.push_back(p[0]);
|
||||||
}
|
}
|
||||||
std::sort(x_coord.begin(), x_coord.end());
|
std::sort(x_coord.begin(), x_coord.end());
|
||||||
|
|
|
@ -48,7 +48,7 @@ TimedPointCloud TransformTimedPointCloud(const TimedPointCloud& point_cloud,
|
||||||
PointCloud CropPointCloud(const PointCloud& point_cloud, const float min_z,
|
PointCloud CropPointCloud(const PointCloud& point_cloud, const float min_z,
|
||||||
const float max_z) {
|
const float max_z) {
|
||||||
PointCloud cropped_point_cloud;
|
PointCloud cropped_point_cloud;
|
||||||
for (const auto& point : point_cloud) {
|
for (const Eigen::Vector3f& point : point_cloud) {
|
||||||
if (min_z <= point.z() && point.z() <= max_z) {
|
if (min_z <= point.z() && point.z() <= max_z) {
|
||||||
cropped_point_cloud.push_back(point);
|
cropped_point_cloud.push_back(point);
|
||||||
}
|
}
|
||||||
|
@ -59,7 +59,7 @@ PointCloud CropPointCloud(const PointCloud& point_cloud, const float min_z,
|
||||||
TimedPointCloud CropTimedPointCloud(const TimedPointCloud& point_cloud,
|
TimedPointCloud CropTimedPointCloud(const TimedPointCloud& point_cloud,
|
||||||
const float min_z, const float max_z) {
|
const float min_z, const float max_z) {
|
||||||
TimedPointCloud cropped_point_cloud;
|
TimedPointCloud cropped_point_cloud;
|
||||||
for (const auto& point : point_cloud) {
|
for (const Eigen::Vector4f& point : point_cloud) {
|
||||||
if (min_z <= point.z() && point.z() <= max_z) {
|
if (min_z <= point.z() && point.z() <= max_z) {
|
||||||
cropped_point_cloud.push_back(point);
|
cropped_point_cloud.push_back(point);
|
||||||
}
|
}
|
||||||
|
|
|
@ -58,11 +58,11 @@ proto::RangeData ToProto(const RangeData& range_data) {
|
||||||
proto::RangeData proto;
|
proto::RangeData proto;
|
||||||
*proto.mutable_origin() = transform::ToProto(range_data.origin);
|
*proto.mutable_origin() = transform::ToProto(range_data.origin);
|
||||||
proto.mutable_returns()->Reserve(range_data.returns.size());
|
proto.mutable_returns()->Reserve(range_data.returns.size());
|
||||||
for (const auto& point : range_data.returns) {
|
for (const Eigen::Vector3f& point : range_data.returns) {
|
||||||
*proto.add_returns() = transform::ToProto(point);
|
*proto.add_returns() = transform::ToProto(point);
|
||||||
}
|
}
|
||||||
proto.mutable_misses()->Reserve(range_data.misses.size());
|
proto.mutable_misses()->Reserve(range_data.misses.size());
|
||||||
for (const auto& point : range_data.misses) {
|
for (const Eigen::Vector3f& point : range_data.misses) {
|
||||||
*proto.add_misses() = transform::ToProto(point);
|
*proto.add_misses() = transform::ToProto(point);
|
||||||
}
|
}
|
||||||
return proto;
|
return proto;
|
||||||
|
|
|
@ -28,7 +28,7 @@ proto::TimedPointCloudData ToProto(
|
||||||
proto.set_timestamp(common::ToUniversal(timed_point_cloud_data.time));
|
proto.set_timestamp(common::ToUniversal(timed_point_cloud_data.time));
|
||||||
*proto.mutable_origin() = transform::ToProto(timed_point_cloud_data.origin);
|
*proto.mutable_origin() = transform::ToProto(timed_point_cloud_data.origin);
|
||||||
proto.mutable_point_data()->Reserve(timed_point_cloud_data.ranges.size());
|
proto.mutable_point_data()->Reserve(timed_point_cloud_data.ranges.size());
|
||||||
for (const auto& range : timed_point_cloud_data.ranges) {
|
for (const Eigen::Vector4f& range : timed_point_cloud_data.ranges) {
|
||||||
*proto.add_point_data() = transform::ToProto(range);
|
*proto.add_point_data() = transform::ToProto(range);
|
||||||
}
|
}
|
||||||
return proto;
|
return proto;
|
||||||
|
|
|
@ -81,7 +81,7 @@ PointCloudType FilterPointCloudUsingVoxels(
|
||||||
const PointCloudType& point_cloud,
|
const PointCloudType& point_cloud,
|
||||||
mapping_3d::HybridGridBase<uint8>* voxels) {
|
mapping_3d::HybridGridBase<uint8>* voxels) {
|
||||||
PointCloudType results;
|
PointCloudType results;
|
||||||
for (const auto& point : point_cloud) {
|
for (const typename PointCloudType::value_type& point : point_cloud) {
|
||||||
auto* const value =
|
auto* const value =
|
||||||
voxels->mutable_value(voxels->GetCellIndex(point.template head<3>()));
|
voxels->mutable_value(voxels->GetCellIndex(point.template head<3>()));
|
||||||
if (*value == 0) {
|
if (*value == 0) {
|
||||||
|
|
Loading…
Reference in New Issue