Skip to content
Open
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
1 change: 1 addition & 0 deletions elevation_mapping/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,7 @@ catkin_package(
## Your package locations should be listed before other locations
include_directories(
include
SYSTEM
${catkin_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${Eigen_INCLUDE_DIRS}
Expand Down
10 changes: 5 additions & 5 deletions elevation_mapping/src/ElevationMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ bool ElevationMap::add(const pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointCloud,
if (initialTime_.toSec() == 0) {
initialTime_ = timestamp;
}
const double scanTimeSinceInitialization = (timestamp - initialTime_).toSec();
double scanTimeSinceInitialization = (timestamp - initialTime_).toSec();

for (unsigned int i = 0; i < pointCloud->size(); ++i) {
auto& point = pointCloud->points[i];
Expand All @@ -100,7 +100,7 @@ bool ElevationMap::add(const pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointCloud,
auto& sensorZatLowestScan = rawMap_.at("sensor_z_at_lowest_scan", index);

const float& pointVariance = pointCloudVariances(i);
const float scanTimeSinceInitialization = (timestamp - initialTime_).toSec();
scanTimeSinceInitialization = (timestamp - initialTime_).toSec();

if (!rawMap_.isValid(index)) {
// No prior information in elevation map, use measurement.
Expand Down Expand Up @@ -414,14 +414,14 @@ void ElevationMap::visibilityCleanup(const ros::Time& updatedTime)
float pointDiffY = point.y() - sensorYatLowestScan;
float distanceToPoint = sqrt(pointDiffX * pointDiffX + pointDiffY * pointDiffY);
if (distanceToPoint > 0.0) {
for (grid_map::LineIterator iterator(visibilityCleanupMap_, indexAtSensor, *iterator); !iterator.isPastEnd(); ++iterator) {
for (grid_map::LineIterator line_iterator(visibilityCleanupMap_, indexAtSensor, *iterator); !line_iterator.isPastEnd(); ++line_iterator) {
Position cellPosition;
visibilityCleanupMap_.getPosition(*iterator, cellPosition);
visibilityCleanupMap_.getPosition(*line_iterator, cellPosition);
const float cellDiffX = cellPosition.x() - sensorXatLowestScan;
const float cellDiffY = cellPosition.y() - sensorYatLowestScan;
const float distanceToCell = distanceToPoint - sqrt(cellDiffX * cellDiffX + cellDiffY * cellDiffY);
const float maxHeightPoint = lowestScanPoint + (sensorZatLowestScan - lowestScanPoint) / distanceToPoint * distanceToCell;
auto& cellMaxHeight = visibilityCleanupMap_.at("max_height", *iterator);
auto& cellMaxHeight = visibilityCleanupMap_.at("max_height", *line_iterator);
if (std::isnan(cellMaxHeight) || cellMaxHeight > maxHeightPoint) {
cellMaxHeight = maxHeightPoint;
}
Expand Down