Skip to content

Commit

Permalink
build(probabilistic_occupancy_grid_map): move header files to the pro…
Browse files Browse the repository at this point in the history
…babilistic_occupancy_grid_map folder to avoid conflicts

Signed-off-by: Esteve Fernandez <[email protected]>
  • Loading branch information
esteve committed Jan 11, 2024
1 parent 73c9e17 commit d7663cf
Show file tree
Hide file tree
Showing 27 changed files with 95 additions and 94 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,8 @@
* Author: Eitan Marder-Eppstein
*********************************************************************/

#ifndef COST_VALUE_HPP_
#define COST_VALUE_HPP_
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__COST_VALUE_HPP_
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__COST_VALUE_HPP_

#include <algorithm>

Expand Down Expand Up @@ -103,4 +103,4 @@ static const CostTranslationTable cost_translation_table;
static const InverseCostTranslationTable inverse_cost_translation_table;
} // namespace occupancy_cost_value

#endif // COST_VALUE_HPP_
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__COST_VALUE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_
#define FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_

#include "cost_value.hpp"
#include "probabilistic_occupancy_grid_map/cost_value.hpp"

#include <cmath>
#include <iostream>
Expand Down Expand Up @@ -63,4 +63,4 @@ unsigned char singleFrameOccupancyFusion(
const std::vector<double> & reliability);
} // namespace fusion_policy

#endif // FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_
#define FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_

#include "fusion/single_frame_fusion_policy.hpp"
#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp"
#include "updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp"
#include "updater/occupancy_grid_map_updater_interface.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/fusion/single_frame_fusion_policy.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/updater/occupancy_grid_map_log_odds_bayes_filter_updater.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp"

#include <builtin_interfaces/msg/time.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down Expand Up @@ -124,4 +124,4 @@ class GridMapFusionNode : public rclcpp::Node

} // namespace synchronized_grid_map_fusion

#endif // FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SYNCHRONIZED_GRID_MAP_FUSION_NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef LASERSCAN_BASED_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_
#define LASERSCAN_BASED_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_

#include "laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp"
#include "updater/occupancy_grid_map_binary_bayes_filter_updater.hpp"
#include "updater/occupancy_grid_map_updater_interface.hpp"
#include "probabilistic_occupancy_grid_map/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp"
#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp"
#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp"

#include <builtin_interfaces/msg/time.hpp>
#include <laser_geometry/laser_geometry.hpp>
Expand Down Expand Up @@ -102,4 +102,4 @@ class LaserscanBasedOccupancyGridMapNode : public rclcpp::Node

} // namespace occupancy_grid_map

#endif // LASERSCAN_BASED_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,8 @@
* David V. Lu!!
*********************************************************************/

#ifndef LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_
#define LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_

#include <nav2_costmap_2d/costmap_2d.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down Expand Up @@ -91,4 +91,4 @@ class OccupancyGridMap : public nav2_costmap_2d::Costmap2D

} // namespace costmap_2d

#endif // LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,8 @@
* David V. Lu!!
*********************************************************************/

#ifndef POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_
#define POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_

#include <nav2_costmap_2d/costmap_2d.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down Expand Up @@ -92,4 +92,4 @@ class OccupancyGridMapInterface : public nav2_costmap_2d::Costmap2D

} // namespace costmap_2d

#endif // POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_
#define POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_

#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp"

namespace costmap_2d
{
Expand Down Expand Up @@ -44,4 +44,4 @@ class OccupancyGridMapFixedBlindSpot : public OccupancyGridMapInterface

} // namespace costmap_2d

#endif // POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_
#define POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_

#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp"

#include <grid_map_core/GridMap.hpp>

Expand Down Expand Up @@ -52,4 +52,4 @@ class OccupancyGridMapProjectiveBlindSpot : public OccupancyGridMapInterface

} // namespace costmap_2d

#endif // POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_
#define POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_

#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp"
#include "updater/occupancy_grid_map_binary_bayes_filter_updater.hpp"
#include "updater/occupancy_grid_map_updater_interface.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp"
#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp"
#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp"

#include <builtin_interfaces/msg/time.hpp>
#include <laser_geometry/laser_geometry.hpp>
Expand Down Expand Up @@ -95,4 +95,4 @@ class PointcloudBasedOccupancyGridMapNode : public rclcpp::Node

} // namespace occupancy_grid_map

#endif // POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP_NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_
#define UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_

#include "updater/occupancy_grid_map_updater_interface.hpp"
#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp"

#include <Eigen/Core>
#include <Eigen/Geometry>
Expand All @@ -39,4 +39,4 @@ class OccupancyGridMapBBFUpdater : public OccupancyGridMapUpdaterInterface

} // namespace costmap_2d

#endif // UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_
#define UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_

#include "fusion/single_frame_fusion_policy.hpp"
#include "updater/occupancy_grid_map_updater_interface.hpp"
#include "utils/utils.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/fusion/single_frame_fusion_policy.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/utils/utils.hpp"

#include <eigen3/Eigen/Core>
#include <eigen3/Eigen/Geometry>
Expand Down Expand Up @@ -45,4 +45,4 @@ class OccupancyGridMapLOBFUpdater : public OccupancyGridMapUpdaterInterface

} // namespace costmap_2d

#endif // UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_
#define UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_

#include "cost_value.hpp"
#include "probabilistic_occupancy_grid_map/cost_value.hpp"

#include <nav2_costmap_2d/costmap_2d.hpp>
#include <rclcpp/node.hpp>
Expand All @@ -38,4 +38,4 @@ class OccupancyGridMapUpdaterInterface : public nav2_costmap_2d::Costmap2D

} // namespace costmap_2d

#endif // UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef UTILS__UTILS_HPP_
#define UTILS__UTILS_HPP_
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_

#include "cost_value.hpp"
#include "probabilistic_occupancy_grid_map/cost_value.hpp"

#include <builtin_interfaces/msg/time.hpp>
#include <pcl_ros/transforms.hpp>
Expand Down Expand Up @@ -119,4 +119,4 @@ bool extractCommonPointCloud(
unsigned char getApproximateOccupancyState(const unsigned char & value);
} // namespace utils

#endif // UTILS__UTILS_HPP_
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "fusion/single_frame_fusion_policy.hpp"
#include "probabilistic_occupancy_grid_map/fusion/single_frame_fusion_policy.hpp"

namespace fusion_policy
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "fusion/synchronized_grid_map_fusion_node.hpp"
#include "probabilistic_occupancy_grid_map/fusion/synchronized_grid_map_fusion_node.hpp"

#include "cost_value.hpp"
#include "utils/utils.hpp"
#include "probabilistic_occupancy_grid_map/cost_value.hpp"
#include "probabilistic_occupancy_grid_map/utils/utils.hpp"

namespace synchronized_grid_map_fusion
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp"
#include "probabilistic_occupancy_grid_map/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.hpp"

#include "cost_value.hpp"
#include "utils/utils.hpp"
#include "probabilistic_occupancy_grid_map/cost_value.hpp"
#include "probabilistic_occupancy_grid_map/utils/utils.hpp"

#include <pcl_ros/transforms.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,9 @@
* David V. Lu!!
*********************************************************************/

#include "laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp"
#include "probabilistic_occupancy_grid_map/laserscan_based_occupancy_grid_map/occupancy_grid_map.hpp"

#include "cost_value.hpp"
#include "probabilistic_occupancy_grid_map/cost_value.hpp"

#include <sensor_msgs/point_cloud2_iterator.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,10 +49,10 @@
* David V. Lu!!
*********************************************************************/

#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp"

#include "cost_value.hpp"
#include "utils/utils.hpp"
#include "probabilistic_occupancy_grid_map/cost_value.hpp"
#include "probabilistic_occupancy_grid_map/utils/utils.hpp"

#include <grid_map_costmap_2d/grid_map_costmap_2d.hpp>
#include <pcl_ros/transforms.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp"

#include "cost_value.hpp"
#include "utils/utils.hpp"
#include "probabilistic_occupancy_grid_map/cost_value.hpp"
#include "probabilistic_occupancy_grid_map/utils/utils.hpp"

#include <grid_map_costmap_2d/grid_map_costmap_2d.hpp>
#include <pcl_ros/transforms.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp"

#include "cost_value.hpp"
#include "utils/utils.hpp"
#include "probabilistic_occupancy_grid_map/cost_value.hpp"
#include "probabilistic_occupancy_grid_map/utils/utils.hpp"

#include <grid_map_costmap_2d/grid_map_costmap_2d.hpp>
#include <grid_map_ros/grid_map_ros.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp"

#include "cost_value.hpp"
#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp"
#include "pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp"
#include "utils/utils.hpp"
#include "probabilistic_occupancy_grid_map/cost_value.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.hpp"
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.hpp"
#include "probabilistic_occupancy_grid_map/utils/utils.hpp"

#include <pcl_ros/transforms.hpp>
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "updater/occupancy_grid_map_binary_bayes_filter_updater.hpp"
#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp"

#include "cost_value.hpp"
#include "probabilistic_occupancy_grid_map/cost_value.hpp"

#include <algorithm>

Expand Down
Loading

0 comments on commit d7663cf

Please sign in to comment.