Skip to content

Commit 053bb4b

Browse files
committed
refactor: update namespace for lib
Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent 229392d commit 053bb4b

21 files changed

+70
-9
lines changed

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

+4
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,8 @@
5353

5454
#include <algorithm>
5555

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

102104
static const CostTranslationTable cost_translation_table;
103105
static const InverseCostTranslationTable inverse_cost_translation_table;
106+
104107
} // namespace cost_value
108+
} // namespace autoware::occupancy_grid_map
105109

106110
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COST_VALUE__COST_VALUE_HPP_

perception/probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -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

9497
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_HPP_

perception/probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_base.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -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

9598
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_BASE_HPP_

perception/probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_fixed.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,8 @@
1717

1818
#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

4750
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_FIXED_HPP_

perception/probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_projective.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,8 @@
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

5558
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_PROJECTIVE_HPP_

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

+4
Original file line numberDiff line numberDiff line change
@@ -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

6670
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__FUSION_POLICY__FUSION_POLICY_HPP_

perception/probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/binary_bayes_filter_updater.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,8 @@
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

4245
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__BINARY_BAYES_FILTER_UPDATER_HPP_

perception/probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/log_odds_bayes_filter_updater.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,8 @@
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

4952
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__LOG_ODDS_BAYES_FILTER_UPDATER_HPP_

perception/probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/ogm_updater_interface.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,8 @@
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
@@ -36,5 +38,6 @@ class OccupancyGridMapUpdaterInterface : public nav2_costmap_2d::Costmap2D
3638
};
3739

3840
} // namespace costmap_2d
41+
} // namespace autoware::occupancy_grid_map
3942

4043
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OGM_UPDATER_INTERFACE_HPP_

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

+4
Original file line numberDiff line numberDiff line change
@@ -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

122126
#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_

perception/probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,8 @@
5757

5858
#include <algorithm>
5959

60+
namespace autoware::occupancy_grid_map
61+
{
6062
namespace costmap_2d
6163
{
6264
using sensor_msgs::PointCloud2ConstIterator;
@@ -250,3 +252,4 @@ void OccupancyGridMap::raytraceFreespace(const PointCloud2 & pointcloud, const P
250252
}
251253

252254
} // namespace costmap_2d
255+
} // namespace autoware::occupancy_grid_map

perception/probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_base.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,9 @@
6969
#endif
7070

7171
#include <algorithm>
72+
73+
namespace autoware::occupancy_grid_map
74+
{
7275
namespace costmap_2d
7376
{
7477
using sensor_msgs::PointCloud2ConstIterator;
@@ -230,3 +233,4 @@ void OccupancyGridMapInterface::raytrace(
230233
}
231234

232235
} // namespace costmap_2d
236+
} // namespace autoware::occupancy_grid_map

perception/probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,9 @@
3333
#endif
3434

3535
#include <algorithm>
36+
37+
namespace autoware::occupancy_grid_map
38+
{
3639
namespace costmap_2d
3740
{
3841
using sensor_msgs::PointCloud2ConstIterator;
@@ -228,3 +231,4 @@ void OccupancyGridMapFixedBlindSpot::initRosParam(rclcpp::Node & node)
228231
}
229232

230233
} // namespace costmap_2d
234+
} // namespace autoware::occupancy_grid_map

perception/probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_projective.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,9 @@
3434
#endif
3535

3636
#include <algorithm>
37+
38+
namespace autoware::occupancy_grid_map
39+
{
3740
namespace costmap_2d
3841
{
3942
using sensor_msgs::PointCloud2ConstIterator;
@@ -299,3 +302,4 @@ void OccupancyGridMapProjectiveBlindSpot::initRosParam(rclcpp::Node & node)
299302
}
300303

301304
} // namespace costmap_2d
305+
} // namespace autoware::occupancy_grid_map

perception/probabilistic_occupancy_grid_map/lib/fusion_policy/fusion_policy.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@
1414

1515
#include "autoware/probabilistic_occupancy_grid_map/fusion_policy/fusion_policy.hpp"
1616

17+
namespace autoware::occupancy_grid_map
18+
{
1719
namespace fusion_policy
1820
{
1921

@@ -320,3 +322,4 @@ unsigned char singleFrameOccupancyFusion(
320322
}
321323

322324
} // namespace fusion_policy
325+
} // namespace autoware::occupancy_grid_map

perception/probabilistic_occupancy_grid_map/lib/updater/binary_bayes_filter_updater.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,8 @@
1818

1919
#include <algorithm>
2020

21+
namespace autoware::occupancy_grid_map
22+
{
2123
namespace costmap_2d
2224
{
2325

@@ -79,3 +81,4 @@ bool OccupancyGridMapBBFUpdater::update(const Costmap2D & single_frame_occupancy
7981
}
8082

8183
} // namespace costmap_2d
84+
} // namespace autoware::occupancy_grid_map

perception/probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,8 @@
2020

2121
// cspell: ignore LOBF
2222

23+
namespace autoware::occupancy_grid_map
24+
{
2325
namespace costmap_2d
2426
{
2527

@@ -68,4 +70,6 @@ bool OccupancyGridMapLOBFUpdater::update(const Costmap2D & single_frame_occupanc
6870
}
6971
return true;
7072
}
73+
7174
} // namespace costmap_2d
75+
} // namespace autoware::occupancy_grid_map

perception/probabilistic_occupancy_grid_map/lib/utils/utils.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,8 @@
1818

1919
#include <string>
2020

21+
namespace autoware::occupancy_grid_map
22+
{
2123
namespace utils
2224
{
2325

@@ -199,3 +201,4 @@ unsigned char getApproximateOccupancyState(const unsigned char & value)
199201
}
200202

201203
} // namespace utils
204+
} // namespace autoware::occupancy_grid_map

perception/probabilistic_occupancy_grid_map/test/cost_value_test.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,8 @@
1717
#include <gtest/gtest.h>
1818

1919
// Test the CostTranslationTable and InverseCostTranslationTable functions
20-
using cost_value::cost_translation_table;
21-
using cost_value::inverse_cost_translation_table;
20+
using autoware::occupancy_grid_map::cost_value::cost_translation_table;
21+
using autoware::occupancy_grid_map::cost_value::inverse_cost_translation_table;
2222

2323
TEST(CostTranslationTableTest, TestRange)
2424
{

perception/probabilistic_occupancy_grid_map/test/fusion_policy_test.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
// Test the log-odds update rule
2222
TEST(FusionPolicyTest, TestLogOddsUpdateRule)
2323
{
24-
using fusion_policy::log_odds_fusion::logOddsFusion;
24+
using autoware::occupancy_grid_map::fusion_policy::log_odds_fusion::logOddsFusion;
2525
const double MARGIN = 0.03;
2626
const double OCCUPIED = 1.0 - MARGIN;
2727
const double FREE = 0.0 + MARGIN;
@@ -50,7 +50,7 @@ TEST(FusionPolicyTest, TestLogOddsUpdateRule)
5050
// Test the dempster-shafer update rule
5151
TEST(FusionPolicyTest, TestDempsterShaferUpdateRule)
5252
{
53-
using fusion_policy::dempster_shafer_fusion::dempsterShaferFusion;
53+
using autoware::occupancy_grid_map::fusion_policy::dempster_shafer_fusion::dempsterShaferFusion;
5454
const double MARGIN = 0.03;
5555
const double OCCUPIED = 1.0 - MARGIN;
5656
const double FREE = 0.0 + MARGIN;

perception/probabilistic_occupancy_grid_map/test/test_utils.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -77,14 +77,14 @@ TEST(TestUtils, TestCropPointcloudByHeight)
7777
sensor_msgs::msg::PointCloud2 test1_output, test2_output, test3_output;
7878

7979
// case1: normal input, normal output
80-
EXPECT_NO_THROW(
81-
utils::cropPointcloudByHeight(ros_cloud_10, mock_buffer, "base_link", 0.0, 10.0, test1_output));
80+
EXPECT_NO_THROW(autoware::occupancy_grid_map::utils::cropPointcloudByHeight(
81+
ros_cloud_10, mock_buffer, "base_link", 0.0, 10.0, test1_output));
8282

8383
// case2: normal input, empty output
84-
EXPECT_NO_THROW(utils::cropPointcloudByHeight(
84+
EXPECT_NO_THROW(autoware::occupancy_grid_map::utils::cropPointcloudByHeight(
8585
ros_cloud_10, mock_buffer, "base_link", -2.0, -0.1, test2_output));
8686

8787
// case3: empty input, normal output
88-
EXPECT_NO_THROW(
89-
utils::cropPointcloudByHeight(ros_cloud_0, mock_buffer, "base_link", 0.0, 10.0, test3_output));
88+
EXPECT_NO_THROW(autoware::occupancy_grid_map::utils::cropPointcloudByHeight(
89+
ros_cloud_0, mock_buffer, "base_link", 0.0, 10.0, test3_output));
9090
}

0 commit comments

Comments
 (0)