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

Warning hunt #383

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
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
6 changes: 3 additions & 3 deletions grid_map_core/src/GridMapMath.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -405,7 +405,7 @@ bool getBufferRegionsForSubmap(std::vector<BufferRegion>& submapBufferRegions,
Size bottomLeftSize(submapBufferSize(0) - topLeftSize(0), bufferSize(1) - submapIndex(1));
submapBufferRegions.emplace_back(bottomLeftIndex, bottomLeftSize, BufferRegion::Quadrant::BottomLeft);

Index bottomRightIndex = Index::Zero();
bottomRightIndex = Index::Zero();
Size bottomRightSize(bottomLeftSize(0), topRightSize(1));
submapBufferRegions.emplace_back(bottomRightIndex, bottomRightSize, BufferRegion::Quadrant::BottomRight);
return true;
Expand All @@ -423,7 +423,7 @@ bool getBufferRegionsForSubmap(std::vector<BufferRegion>& submapBufferRegions,
Size topRightSize(bufferSize(0) - submapIndex(0), submapBufferSize(1));
submapBufferRegions.emplace_back(submapIndex, topRightSize, BufferRegion::Quadrant::TopRight);

Index bottomRightIndex(0, submapIndex(1));
bottomRightIndex(0, submapIndex(1));
Size bottomRightSize(submapBufferSize(0) - topRightSize(0), submapBufferSize(1));
submapBufferRegions.emplace_back(bottomRightIndex, bottomRightSize, BufferRegion::Quadrant::BottomRight);
return true;
Expand All @@ -440,7 +440,7 @@ bool getBufferRegionsForSubmap(std::vector<BufferRegion>& submapBufferRegions,
Size bottomLeftSize(submapBufferSize(0), bufferSize(1) - submapIndex(1));
submapBufferRegions.emplace_back(submapIndex, bottomLeftSize, BufferRegion::Quadrant::BottomLeft);

Index bottomRightIndex(submapIndex(0), 0);
bottomRightIndex(submapIndex(0), 0);
Size bottomRightSize(submapBufferSize(0), submapBufferSize(1) - bottomLeftSize(1));
submapBufferRegions.emplace_back(bottomRightIndex, bottomRightSize, BufferRegion::Quadrant::BottomRight);
return true;
Expand Down
2 changes: 1 addition & 1 deletion grid_map_cv/include/grid_map_cv/InpaintFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@

#pragma once

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>

//OpenCV
#include "grid_map_cv/grid_map_cv.hpp"
Expand Down
1 change: 1 addition & 0 deletions grid_map_demos/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ catkin_package(
## Your package locations should be listed before other locations
include_directories(
include
SYSTEM
${catkin_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIR}
${OCTOMAP_INCLUDE_DIR}
Expand Down
2 changes: 1 addition & 1 deletion grid_map_demos/include/grid_map_demos/FiltersDemo.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpedantic"
#pragma GCC diagnostic ignored "-Wformat"
#include <filters/filter_chain.hpp>
#include <filters/filter_chain.h>
#pragma GCC diagnostic pop
#include <ros/ros.h>
#include <string>
Expand Down
2 changes: 1 addition & 1 deletion grid_map_demos/src/InterpolationDemo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ AnalyticalFunctions createGaussianWorld(grid_map::GridMap *map)
0.1, 0.1 }, { 0.1, 0.1 }, { 0.1, 0.1 }, { 0.1, 0.05 }, { 0.05, 0.05 } } };
std::array<std::pair<double, double>, numGaussians> means = { { { 1, -1 }, { 1, 1.7 },
{ -1, 1.6 }, { -1.8, -1.8 }, { -1, 1.8 }, { 0, 0 }, { -1.2, 0 } } };
std::array<double, numGaussians> scales = { -2.0, -1.0, 2.0, 1.0, 3.0, 4.0, 1.0 };
std::array<double, numGaussians> scales = {{ -2.0, -1.0, 2.0, 1.0, 3.0, 4.0, 1.0 }};

std::array<Gaussian, numGaussians> g;

Expand Down
2 changes: 1 addition & 1 deletion grid_map_demos/src/normal_filter_comparison_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpedantic"
#pragma GCC diagnostic ignored "-Wformat"
#include <filters/filter_chain.hpp>
#include <filters/filter_chain.h>
#pragma GCC diagnostic pop
#include <ros/ros.h>
#include <Eigen/Core>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

#include <string>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <Eigen/Core>
#include <string>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

#include <Eigen/Core>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <Eigen/Core>
#include <string>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>
#include <grid_map_core/TypeDefs.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <Eigen/Core>
#include <string>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <string>
#include <vector>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

#include <string>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <Eigen/Core>
#include <string>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <string>
#include "EigenLab/EigenLab.h"

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

#include <string>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <Eigen/Core>
#include <string>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>
#include <grid_map_core/TypeDefs.hpp>
#include <opencv2/core.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

#include <string>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
2 changes: 1 addition & 1 deletion grid_map_filters/include/grid_map_filters/MockFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

#include <string>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <Eigen/Core>
#include <string>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <Eigen/Core>
#include <string>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/grid_map_core.hpp>

namespace grid_map {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <string>
#include <vector>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <Eigen/Core>
#include <string>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/grid_map_core.hpp>

#include "EigenLab/EigenLab.h"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <string>
#include <vector>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>

namespace grid_map {
Expand Down
2 changes: 1 addition & 1 deletion grid_map_filters/test/median_fill_filter_test.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include <gmock/gmock.h>
#include <gtest/gtest.h>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>
#include <grid_map_core/utils/testing.hpp>

Expand Down
2 changes: 1 addition & 1 deletion grid_map_filters/test/threshold_filter_test.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include <gmock/gmock.h>
#include <gtest/gtest.h>

#include <filters/filter_base.hpp>
#include <filters/filter_base.h>
#include <grid_map_core/GridMap.hpp>
#include <grid_map_core/utils/testing.hpp>

Expand Down
1 change: 1 addition & 0 deletions grid_map_loader/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ install(
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
install(DIRECTORY ${PROJECT_SOURCE_DIR}/include DESTINATION include)

#############
## Testing ##
Expand Down
4 changes: 2 additions & 2 deletions grid_map_octomap/src/GridMapOctomapConverter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,9 +96,9 @@ bool GridMapOctomapConverter::fromOctomap(const octomap::OcTree& octomap,
end = octomapCopy.end_leafs_bbx(); it != end; ++it) {
if (octomapCopy.isNodeOccupied(*it)) {
octomap::point3d octoPos = it.getCoordinate();
grid_map::Position position(octoPos.x(), octoPos.y());
grid_map::Position gridm_position(octoPos.x(), octoPos.y());
grid_map::Index index;
gridMap.getIndex(position, index);
gridMap.getIndex(gridm_position, index);
// If no elevation has been set, use current elevation.
if (!gridMap.isValid(index)) {
gridMapData(index(0), index(1)) = octoPos.z();
Expand Down
2 changes: 1 addition & 1 deletion grid_map_pcl/src/GridMapPclLoader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@ void GridMapPclLoader::calculateElevationFromPointsInsideGridMapCell(Pointcloud:
heights.reserve(clusterClouds.size());

std::transform(clusterClouds.begin(), clusterClouds.end(), std::back_inserter(heights),
[this](Pointcloud::ConstPtr cloud) -> double { return grid_map_pcl::calculateMeanOfPointPositions(cloud).z(); });
[this](Pointcloud::ConstPtr my_cloud) -> double { return grid_map_pcl::calculateMeanOfPointPositions(my_cloud).z(); });
}

GridMapPclLoader::Pointcloud::Ptr GridMapPclLoader::getPointcloudInsideGridMapCellBorder(const grid_map::Index& index) const {
Expand Down
4 changes: 2 additions & 2 deletions grid_map_rviz_plugin/src/GridMapDisplay.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,7 +214,7 @@ void GridMapDisplay::updateVisualization()
bool noColor = colorModeProperty_->getOptionInt() == 3;
Ogre::ColourValue meshColor = colorProperty_->getOgreColor();
std::string colorLayer = colorTransformerProperty_->getStdString();
std::string colorMap = colorMapProperty_->getStdString();
std::string colorMapStr = colorMapProperty_->getStdString();
bool useColorMap = useColorMapProperty_->getBool();
bool invertColorMap = invertColorMapProperty_->getBool();
Ogre::ColourValue minColor = minColorProperty_->getOgreColor();
Expand All @@ -227,7 +227,7 @@ void GridMapDisplay::updateVisualization()

for (size_t i = 0; i < visuals_.size(); i++) {
visuals_[i]->computeVisualization(alpha, showGridLines, flatTerrain, heightLayer, flatColor, noColor, meshColor, mapLayerColor,
colorLayer, colorMap, useColorMap, invertColorMap, minColor, maxColor, autocomputeIntensity, minIntensity,
colorLayer, colorMapStr, useColorMap, invertColorMap, minColor, maxColor, autocomputeIntensity, minIntensity,
maxIntensity, gridLineThickness, gridCellDecimation);
}
}
Expand Down
10 changes: 5 additions & 5 deletions grid_map_rviz_plugin/src/GridMapVisual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ void GridMapVisual::setMessage(const grid_map_msgs::GridMap::ConstPtr& msg) {

void GridMapVisual::computeVisualization(float alpha, bool showGridLines, bool flatTerrain, std::string heightLayer, bool flatColor,
bool noColor, Ogre::ColourValue meshColor, bool mapLayerColor, std::string colorLayer,
std::string colorMap, bool useColorMap, bool invertColorMap, Ogre::ColourValue minColor,
std::string colorMapStr, bool useColorMap, bool invertColorMap, Ogre::ColourValue minColor,
Ogre::ColourValue maxColor, bool autocomputeIntensity, float minIntensity, float maxIntensity, float gridLineThickness,
int gridCellDecimation) {
const auto startTime = std::chrono::high_resolution_clock::now();
Expand Down Expand Up @@ -130,7 +130,7 @@ void GridMapVisual::computeVisualization(float alpha, bool showGridLines, bool f
coloringMethod = ColoringMethod::INTENSITY_LAYER_INVERTED_COLORMAP;
}

const auto colorValues = computeColorValues(heightData, colorData, coloringMethod, colorMap, meshColor,
const auto colorValues = computeColorValues(heightData, colorData, coloringMethod, colorMapStr, meshColor,
minIntensity, maxIntensity, autocomputeIntensity, minColor, maxColor);

// Initialize loop constants.
Expand Down Expand Up @@ -171,11 +171,11 @@ void GridMapVisual::computeVisualization(float alpha, bool showGridLines, bool f
std::vector<int> vertexIndices;
for (size_t k = 0; k < 2; k++) {
for (size_t l = 0; l < 2; l++) {
grid_map::Index index(i - k, j - l);
if (!isValid(index(0), index(1))) {
grid_map::Index my_index(i - k, j - l);
if (!isValid(my_index(0), my_index(1))) {
continue;
}
vertexIndices.emplace_back(indexToOgreIndex(index(0), index(1)));
vertexIndices.emplace_back(indexToOgreIndex(my_index(0), my_index(1)));
}
}

Expand Down
2 changes: 1 addition & 1 deletion grid_map_sdf/include/grid_map_sdf/Gridmap3dLookup.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ struct Gridmap3dLookup {
size_t z{0};

size_t_3d() = default;
size_t_3d(size_t x, size_t y, size_t z) : x(x), y(y), z(z) {}
size_t_3d(size_t in_x, size_t in_y, size_t in_z) : x(in_x), y(in_y), z(in_z) {}
};

//! 3D size of the grid
Expand Down
2 changes: 1 addition & 1 deletion grid_map_sdf/src/SignedDistanceField.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ void SignedDistanceField::emplacebackLayerData(const Matrix& signedDistance, con
const Matrix& dz) {
for (size_t colY = 0; colY < gridmap3DLookup_.gridsize_.y; ++colY) {
for (size_t rowX = 0; rowX < gridmap3DLookup_.gridsize_.x; ++rowX) {
data_.emplace_back(node_data_t{signedDistance(rowX, colY), dxTranspose(colY, rowX), dy(rowX, colY), dz(rowX, colY)});
data_.emplace_back(node_data_t{{signedDistance(rowX, colY), dxTranspose(colY, rowX), dy(rowX, colY), dz(rowX, colY)}});
}
}
}
Expand Down
1 change: 1 addition & 0 deletions grid_map_visualization/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,7 @@ install(
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
install(DIRECTORY ${PROJECT_SOURCE_DIR}/include DESTINATION include)

# Mark other files for installation
install(
Expand Down