Skip to content

Commit 76c69f7

Browse files
technolojinAriiees
authored andcommitted
refactor(probabilistic_occupancy_grid_map)!: fix namespace and directory structure (autowarefoundation#7872)
* refactor: update include paths for probabilistic occupancy grid map Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: update include paths for probabilistic occupancy grid map Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: update namespace for nodes Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: update namespace for lib Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: remove unused dependency Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: use const pointer for occupancy grid map data Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> --------- Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent fb6a144 commit 76c69f7

32 files changed

+241
-183
lines changed

perception/probabilistic_occupancy_grid_map/CMakeLists.txt

+18-17
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,8 @@ include_directories(
1414
)
1515

1616
ament_auto_add_library(${PROJECT_NAME}_common SHARED
17-
src/updater/occupancy_grid_map_binary_bayes_filter_updater.cpp
18-
src/utils/utils.cpp
17+
lib/updater/binary_bayes_filter_updater.cpp
18+
lib/utils/utils.cpp
1919
)
2020
target_link_libraries(${PROJECT_NAME}_common
2121
${PCL_LIBRARIES}
@@ -24,9 +24,9 @@ target_link_libraries(${PROJECT_NAME}_common
2424
# PointcloudBasedOccupancyGridMap
2525
ament_auto_add_library(pointcloud_based_occupancy_grid_map SHARED
2626
src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp
27-
src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.cpp
28-
src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp
29-
src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp
27+
lib/costmap_2d/occupancy_grid_map_base.cpp
28+
lib/costmap_2d/occupancy_grid_map_fixed.cpp
29+
lib/costmap_2d/occupancy_grid_map_projective.cpp
3030
)
3131

3232
target_link_libraries(pointcloud_based_occupancy_grid_map
@@ -35,14 +35,14 @@ target_link_libraries(pointcloud_based_occupancy_grid_map
3535
)
3636

3737
rclcpp_components_register_node(pointcloud_based_occupancy_grid_map
38-
PLUGIN "occupancy_grid_map::PointcloudBasedOccupancyGridMapNode"
38+
PLUGIN "autoware::occupancy_grid_map::PointcloudBasedOccupancyGridMapNode"
3939
EXECUTABLE pointcloud_based_occupancy_grid_map_node
4040
)
4141

4242
# LaserscanBasedOccupancyGridMap
4343
ament_auto_add_library(laserscan_based_occupancy_grid_map SHARED
4444
src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp
45-
src/laserscan_based_occupancy_grid_map/occupancy_grid_map.cpp
45+
lib/costmap_2d/occupancy_grid_map.cpp
4646
)
4747

4848
target_link_libraries(laserscan_based_occupancy_grid_map
@@ -51,25 +51,25 @@ target_link_libraries(laserscan_based_occupancy_grid_map
5151
)
5252

5353
rclcpp_components_register_node(laserscan_based_occupancy_grid_map
54-
PLUGIN "occupancy_grid_map::LaserscanBasedOccupancyGridMapNode"
54+
PLUGIN "autoware::occupancy_grid_map::LaserscanBasedOccupancyGridMapNode"
5555
EXECUTABLE laserscan_based_occupancy_grid_map_node
5656
)
5757

5858
# GridMapFusionNode
5959
ament_auto_add_library(synchronized_grid_map_fusion SHARED
6060
src/fusion/synchronized_grid_map_fusion_node.cpp
61-
src/fusion/single_frame_fusion_policy.cpp
62-
src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp
63-
src/updater/occupancy_grid_map_log_odds_bayes_filter_updater.cpp
64-
src/utils/utils.cpp
61+
lib/fusion_policy/fusion_policy.cpp
62+
lib/costmap_2d/occupancy_grid_map_fixed.cpp
63+
lib/updater/log_odds_bayes_filter_updater.cpp
64+
lib/utils/utils.cpp
6565
)
6666

6767
target_link_libraries(synchronized_grid_map_fusion
6868
${PCL_LIBRARIES}
6969
)
7070

7171
rclcpp_components_register_node(synchronized_grid_map_fusion
72-
PLUGIN "synchronized_grid_map_fusion::GridMapFusionNode"
72+
PLUGIN "autoware::occupancy_grid_map::GridMapFusionNode"
7373
EXECUTABLE synchronized_grid_map_fusion_node
7474
)
7575

@@ -88,13 +88,14 @@ if(BUILD_TESTING)
8888

8989
# gtest
9090
ament_add_gtest(test_utils
91-
test/test_utils.cpp
91+
test/test_utils.cpp
9292
)
9393
ament_add_gtest(costmap_unit_tests
94-
test/cost_value_test.cpp)
94+
test/cost_value_test.cpp
95+
)
9596
ament_add_gtest(fusion_policy_unit_tests
96-
test/fusion_policy_test.cpp
97-
src/fusion/single_frame_fusion_policy.cpp
97+
test/fusion_policy_test.cpp
98+
lib/fusion_policy/fusion_policy.cpp
9899
)
99100
target_link_libraries(test_utils
100101
${PCL_LIBRARIES}

perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/cost_value.hpp perception/probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/cost_value/cost_value.hpp

+9-5
Original file line numberDiff line numberDiff line change
@@ -48,12 +48,14 @@
4848
* Author: Eitan Marder-Eppstein
4949
*********************************************************************/
5050

51-
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__COST_VALUE_HPP_
52-
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__COST_VALUE_HPP_
51+
#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COST_VALUE__COST_VALUE_HPP_
52+
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COST_VALUE__COST_VALUE_HPP_
5353

5454
#include <algorithm>
5555

56-
namespace occupancy_cost_value
56+
namespace autoware::occupancy_grid_map
57+
{
58+
namespace cost_value
5759
{
5860
static const unsigned char NO_INFORMATION = 128; // 0.5 * 255
5961
static const unsigned char LETHAL_OBSTACLE = 255;
@@ -101,6 +103,8 @@ struct InverseCostTranslationTable
101103

102104
static const CostTranslationTable cost_translation_table;
103105
static const InverseCostTranslationTable inverse_cost_translation_table;
104-
} // namespace occupancy_cost_value
105106

106-
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__COST_VALUE_HPP_
107+
} // namespace cost_value
108+
} // namespace autoware::occupancy_grid_map
109+
110+
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COST_VALUE__COST_VALUE_HPP_
Original file line numberDiff line numberDiff line change
@@ -49,8 +49,8 @@
4949
* David V. Lu!!
5050
*********************************************************************/
5151

52-
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_
53-
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_
52+
#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_HPP_
53+
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_HPP_
5454

5555
#include <nav2_costmap_2d/costmap_2d.hpp>
5656
#include <rclcpp/rclcpp.hpp>
@@ -59,6 +59,8 @@
5959
#include <sensor_msgs/msg/laser_scan.hpp>
6060
#include <sensor_msgs/msg/point_cloud2.hpp>
6161

62+
namespace autoware::occupancy_grid_map
63+
{
6264
namespace costmap_2d
6365
{
6466
using geometry_msgs::msg::Pose;
@@ -90,5 +92,6 @@ class OccupancyGridMap : public nav2_costmap_2d::Costmap2D
9092
};
9193

9294
} // namespace costmap_2d
95+
} // namespace autoware::occupancy_grid_map
9396

94-
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__LASERSCAN_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_HPP_
97+
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_HPP_
Original file line numberDiff line numberDiff line change
@@ -49,8 +49,8 @@
4949
* David V. Lu!!
5050
*********************************************************************/
5151

52-
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_
53-
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_
52+
#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_BASE_HPP_
53+
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_BASE_HPP_
5454

5555
#include <nav2_costmap_2d/costmap_2d.hpp>
5656
#include <rclcpp/rclcpp.hpp>
@@ -59,6 +59,8 @@
5959
#include <sensor_msgs/msg/laser_scan.hpp>
6060
#include <sensor_msgs/msg/point_cloud2.hpp>
6161

62+
namespace autoware::occupancy_grid_map
63+
{
6264
namespace costmap_2d
6365
{
6466
using geometry_msgs::msg::Pose;
@@ -91,5 +93,6 @@ class OccupancyGridMapInterface : public nav2_costmap_2d::Costmap2D
9193
};
9294

9395
} // namespace costmap_2d
96+
} // namespace autoware::occupancy_grid_map
9497

95-
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_BASE_HPP_
98+
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_BASE_HPP_
Original file line numberDiff line numberDiff line change
@@ -12,11 +12,13 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_
16-
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_
15+
#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_FIXED_HPP_
16+
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_FIXED_HPP_
1717

18-
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp"
18+
#include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_base.hpp"
1919

20+
namespace autoware::occupancy_grid_map
21+
{
2022
namespace costmap_2d
2123
{
2224
using geometry_msgs::msg::Pose;
@@ -43,5 +45,6 @@ class OccupancyGridMapFixedBlindSpot : public OccupancyGridMapInterface
4345
};
4446

4547
} // namespace costmap_2d
48+
} // namespace autoware::occupancy_grid_map
4649

47-
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_FIXED_HPP_
50+
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_FIXED_HPP_
Original file line numberDiff line numberDiff line change
@@ -12,15 +12,17 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_
16-
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_
15+
#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_
16+
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_
1717

18-
#include "probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/occupancy_grid_map_base.hpp"
18+
#include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_base.hpp"
1919

2020
#include <grid_map_core/GridMap.hpp>
2121

2222
#include <grid_map_msgs/msg/grid_map.hpp>
2323

24+
namespace autoware::occupancy_grid_map
25+
{
2426
namespace costmap_2d
2527
{
2628
using geometry_msgs::msg::Pose;
@@ -51,5 +53,6 @@ class OccupancyGridMapProjectiveBlindSpot : public OccupancyGridMapInterface
5153
};
5254

5355
} // namespace costmap_2d
56+
} // namespace autoware::occupancy_grid_map
5457

55-
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__POINTCLOUD_BASED_OCCUPANCY_GRID_MAP__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_
58+
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_

perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/fusion/single_frame_fusion_policy.hpp perception/probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/fusion_policy/fusion_policy.hpp

+8-4
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_
16-
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_
15+
#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION_POLICY__FUSION_POLICY_HPP_
16+
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION_POLICY__FUSION_POLICY_HPP_
1717

18-
#include "probabilistic_occupancy_grid_map/cost_value.hpp"
18+
#include "autoware/probabilistic_occupancy_grid_map/cost_value/cost_value.hpp"
1919

2020
#include <cmath>
2121
#include <iostream>
@@ -25,6 +25,8 @@
2525
/*min and max prob threshold to prevent log-odds to diverge*/
2626
#define EPSILON_PROB 0.03
2727

28+
namespace autoware::occupancy_grid_map
29+
{
2830
namespace fusion_policy
2931
{
3032
enum class FusionMethod { OVERWRITE, LOG_ODDS, DEMPSTER_SHAFER };
@@ -61,6 +63,8 @@ unsigned char singleFrameOccupancyFusion(
6163
unsigned char singleFrameOccupancyFusion(
6264
const std::vector<unsigned char> & occupancy, FusionMethod method,
6365
const std::vector<double> & reliability);
66+
6467
} // namespace fusion_policy
68+
} // namespace autoware::occupancy_grid_map
6569

66-
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION__SINGLE_FRAME_FUSION_POLICY_HPP_
70+
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION_POLICY__FUSION_POLICY_HPP_
Original file line numberDiff line numberDiff line change
@@ -12,14 +12,16 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_
16-
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_
15+
#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__BINARY_BAYES_FILTER_UPDATER_HPP_
16+
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__BINARY_BAYES_FILTER_UPDATER_HPP_
1717

18-
#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp"
18+
#include "autoware/probabilistic_occupancy_grid_map/updater/ogm_updater_interface.hpp"
1919

2020
#include <Eigen/Core>
2121
#include <Eigen/Geometry>
2222

23+
namespace autoware::occupancy_grid_map
24+
{
2325
namespace costmap_2d
2426
{
2527
class OccupancyGridMapBBFUpdater : public OccupancyGridMapUpdaterInterface
@@ -38,5 +40,6 @@ class OccupancyGridMapBBFUpdater : public OccupancyGridMapUpdaterInterface
3840
};
3941

4042
} // namespace costmap_2d
43+
} // namespace autoware::occupancy_grid_map
4144

42-
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_
45+
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__BINARY_BAYES_FILTER_UPDATER_HPP_
Original file line numberDiff line numberDiff line change
@@ -12,19 +12,21 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_
16-
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_
15+
#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__LOG_ODDS_BAYES_FILTER_UPDATER_HPP_
16+
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__LOG_ODDS_BAYES_FILTER_UPDATER_HPP_
1717

18-
#include "probabilistic_occupancy_grid_map/fusion/single_frame_fusion_policy.hpp"
19-
#include "probabilistic_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp"
20-
#include "probabilistic_occupancy_grid_map/utils/utils.hpp"
18+
#include "autoware/probabilistic_occupancy_grid_map/fusion_policy/fusion_policy.hpp"
19+
#include "autoware/probabilistic_occupancy_grid_map/updater/ogm_updater_interface.hpp"
20+
#include "autoware/probabilistic_occupancy_grid_map/utils/utils.hpp"
2121

2222
#include <eigen3/Eigen/Core>
2323
#include <eigen3/Eigen/Geometry>
2424

2525
// LOBF means: Log Odds Bayes Filter
2626
// cspell: ignore LOBF
2727

28+
namespace autoware::occupancy_grid_map
29+
{
2830
namespace costmap_2d
2931
{
3032
class OccupancyGridMapLOBFUpdater : public OccupancyGridMapUpdaterInterface
@@ -45,5 +47,6 @@ class OccupancyGridMapLOBFUpdater : public OccupancyGridMapUpdaterInterface
4547
};
4648

4749
} // namespace costmap_2d
50+
} // namespace autoware::occupancy_grid_map
4851

49-
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_LOG_ODDS_BAYES_FILTER_UPDATER_HPP_
52+
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__LOG_ODDS_BAYES_FILTER_UPDATER_HPP_
Original file line numberDiff line numberDiff line change
@@ -12,23 +12,24 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_
16-
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_
15+
#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OGM_UPDATER_INTERFACE_HPP_
16+
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OGM_UPDATER_INTERFACE_HPP_
1717

18-
#include "probabilistic_occupancy_grid_map/cost_value.hpp"
18+
#include "autoware/probabilistic_occupancy_grid_map/cost_value/cost_value.hpp"
1919

2020
#include <nav2_costmap_2d/costmap_2d.hpp>
2121
#include <rclcpp/node.hpp>
2222

23+
namespace autoware::occupancy_grid_map
24+
{
2325
namespace costmap_2d
2426
{
2527
class OccupancyGridMapUpdaterInterface : public nav2_costmap_2d::Costmap2D
2628
{
2729
public:
2830
OccupancyGridMapUpdaterInterface(
2931
const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution)
30-
: Costmap2D(
31-
cells_size_x, cells_size_y, resolution, 0.f, 0.f, occupancy_cost_value::NO_INFORMATION)
32+
: Costmap2D(cells_size_x, cells_size_y, resolution, 0.f, 0.f, cost_value::NO_INFORMATION)
3233
{
3334
}
3435
virtual ~OccupancyGridMapUpdaterInterface() = default;
@@ -37,5 +38,6 @@ class OccupancyGridMapUpdaterInterface : public nav2_costmap_2d::Costmap2D
3738
};
3839

3940
} // namespace costmap_2d
41+
} // namespace autoware::occupancy_grid_map
4042

41-
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_UPDATER_INTERFACE_HPP_
43+
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OGM_UPDATER_INTERFACE_HPP_

perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/utils/utils.hpp perception/probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/utils/utils.hpp

+8-4
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_
16-
#define PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_
15+
#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_
16+
#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_
1717

18-
#include "probabilistic_occupancy_grid_map/cost_value.hpp"
18+
#include "autoware/probabilistic_occupancy_grid_map/cost_value/cost_value.hpp"
1919

2020
#include <builtin_interfaces/msg/time.hpp>
2121
#include <pcl_ros/transforms.hpp>
@@ -45,6 +45,8 @@
4545
#include <cmath>
4646
#include <vector>
4747

48+
namespace autoware::occupancy_grid_map
49+
{
4850
namespace utils
4951
{
5052

@@ -117,6 +119,8 @@ bool extractCommonPointCloud(
117119
sensor_msgs::msg::PointCloud2 & output_obstacle_pc);
118120

119121
unsigned char getApproximateOccupancyState(const unsigned char & value);
122+
120123
} // namespace utils
124+
} // namespace autoware::occupancy_grid_map
121125

122-
#endif // PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_
126+
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_

0 commit comments

Comments
 (0)