Skip to content

Commit d187722

Browse files
mkqudakosuke55
andauthored
test(costmap_generator): unit test implementation for costmap generator (#9149)
* modify costmap generator directory structure Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp> * rename class CostmapGenerator to CostmapGeneratorNode Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp> * unit test for object_map_utils Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp> * catch error from lookupTransform Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp> * use polling subscriber in costmap generator node Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp> * add test for costmap generator node Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp> * add test for isActive() Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp> * revert unnecessary changes Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp> * remove commented out line Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp> * minor fix Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp> * Update planning/autoware_costmap_generator/src/costmap_generator.cpp Co-authored-by: Kosuke Takeuchi <kosuke.tnp@gmail.com> --------- Signed-off-by: mohammad alqudah <alqudah.mohammad@tier4.jp> Co-authored-by: Kosuke Takeuchi <kosuke.tnp@gmail.com>
1 parent a3b2723 commit d187722

15 files changed

+844
-365
lines changed

common/autoware_test_utils/test_map/overlap_map.osm

+330-227
Large diffs are not rendered by default.

planning/autoware_costmap_generator/CMakeLists.txt

+19-15
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,9 @@ include_directories(
1616
)
1717

1818
ament_auto_add_library(costmap_generator_lib SHARED
19-
nodes/autoware_costmap_generator/points_to_costmap.cpp
20-
nodes/autoware_costmap_generator/objects_to_costmap.cpp
21-
nodes/autoware_costmap_generator/object_map_utils.cpp
19+
src/utils/points_to_costmap.cpp
20+
src/utils/objects_to_costmap.cpp
21+
src/utils/object_map_utils.cpp
2222
)
2323
target_link_libraries(costmap_generator_lib
2424
${PCL_LIBRARIES}
@@ -37,7 +37,7 @@ generate_parameter_library(costmap_generator_node_parameters
3737
)
3838

3939
ament_auto_add_library(costmap_generator_node SHARED
40-
nodes/autoware_costmap_generator/costmap_generator_node.cpp
40+
src/costmap_generator.cpp
4141
)
4242
target_link_libraries(costmap_generator_node
4343
${PCL_LIBRARIES}
@@ -56,25 +56,29 @@ rclcpp_components_register_node(costmap_generator_node
5656
if(BUILD_TESTING)
5757
find_package(ament_cmake_ros REQUIRED)
5858

59-
ament_add_ros_isolated_gtest(test_points_to_costmap
59+
ament_add_ros_isolated_gtest(test_costmap_generator_lib
6060
test/test_points_to_costmap.cpp
61+
test/test_objects_to_costmap.cpp
62+
test/test_object_map_utils.cpp
6163
)
62-
63-
target_link_libraries(test_points_to_costmap
64+
target_link_libraries(test_costmap_generator_lib
6465
costmap_generator_lib
6566
)
6667

67-
ament_add_ros_isolated_gtest(test_objects_to_costmap
68-
test/test_objects_to_costmap.cpp
68+
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
69+
test/test_costmap_generator.cpp
6970
)
70-
71-
target_link_libraries(test_objects_to_costmap
72-
costmap_generator_lib
71+
target_link_libraries(test_${PROJECT_NAME}
72+
costmap_generator_node
73+
costmap_generator_node_parameters
74+
)
75+
target_compile_options(test_${PROJECT_NAME} PUBLIC
76+
-Wno-error=deprecated-declarations
7377
)
7478
endif()
7579

7680
ament_auto_package(
77-
INSTALL_TO_SHARE
78-
launch
79-
config
81+
INSTALL_TO_SHARE
82+
launch
83+
config
8084
)

planning/autoware_costmap_generator/include/autoware_costmap_generator/costmap_generator.hpp planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp

+23-21
Original file line numberDiff line numberDiff line change
@@ -42,13 +42,14 @@
4242
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
4343
********************/
4444

45-
#ifndef AUTOWARE_COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_
46-
#define AUTOWARE_COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_
45+
#ifndef AUTOWARE__COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_
46+
#define AUTOWARE__COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_
4747

48-
#include "autoware_costmap_generator/objects_to_costmap.hpp"
49-
#include "autoware_costmap_generator/points_to_costmap.hpp"
48+
#include "autoware/costmap_generator/utils/objects_to_costmap.hpp"
49+
#include "autoware/costmap_generator/utils/points_to_costmap.hpp"
5050
#include "costmap_generator_node_parameters.hpp"
5151

52+
#include <autoware/universe_utils/ros/polling_subscriber.hpp>
5253
#include <autoware/universe_utils/ros/processing_time_publisher.hpp>
5354
#include <autoware/universe_utils/system/stop_watch.hpp>
5455
#include <autoware/universe_utils/system/time_keeper.hpp>
@@ -72,8 +73,12 @@
7273
#include <memory>
7374
#include <vector>
7475

76+
class TestCostmapGenerator;
77+
7578
namespace autoware::costmap_generator
7679
{
80+
using autoware_perception_msgs::msg::PredictedObjects;
81+
7782
class CostmapGenerator : public rclcpp::Node
7883
{
7984
public:
@@ -82,9 +87,10 @@ class CostmapGenerator : public rclcpp::Node
8287
private:
8388
std::shared_ptr<::costmap_generator_node::ParamListener> param_listener_;
8489
std::shared_ptr<::costmap_generator_node::Params> param_;
90+
geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_;
8591

8692
lanelet::LaneletMapPtr lanelet_map_;
87-
autoware_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_;
93+
PredictedObjects::ConstSharedPtr objects_;
8894
sensor_msgs::msg::PointCloud2::ConstSharedPtr points_;
8995

9096
grid_map::GridMap costmap_;
@@ -95,10 +101,13 @@ class CostmapGenerator : public rclcpp::Node
95101
rclcpp::Publisher<autoware::universe_utils::ProcessingTimeDetail>::SharedPtr pub_processing_time_;
96102
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr pub_processing_time_ms_;
97103

98-
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_points_;
99-
rclcpp::Subscription<autoware_perception_msgs::msg::PredictedObjects>::SharedPtr sub_objects_;
100104
rclcpp::Subscription<autoware_map_msgs::msg::LaneletMapBin>::SharedPtr sub_lanelet_bin_map_;
101-
rclcpp::Subscription<tier4_planning_msgs::msg::Scenario>::SharedPtr sub_scenario_;
105+
autoware::universe_utils::InterProcessPollingSubscriber<sensor_msgs::msg::PointCloud2>
106+
sub_points_{this, "~/input/points_no_ground", autoware::universe_utils::SingleDepthSensorQoS()};
107+
autoware::universe_utils::InterProcessPollingSubscriber<PredictedObjects> sub_objects_{
108+
this, "~/input/objects"};
109+
autoware::universe_utils::InterProcessPollingSubscriber<tier4_planning_msgs::msg::Scenario>
110+
sub_scenario_{this, "~/input/scenario"};
102111

103112
rclcpp::TimerBase::SharedPtr timer_;
104113

@@ -126,17 +135,9 @@ class CostmapGenerator : public rclcpp::Node
126135
/// \brief callback for loading lanelet2 map
127136
void onLaneletMapBin(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg);
128137

129-
/// \brief callback for DynamicObjectArray
130-
/// \param[in] in_objects input DynamicObjectArray usually from prediction or perception
131-
/// component
132-
void onObjects(const autoware_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg);
138+
void update_data();
133139

134-
/// \brief callback for sensor_msgs::PointCloud2
135-
/// \param[in] in_points input sensor_msgs::PointCloud2. Assuming ground-filtered pointcloud
136-
/// by default
137-
void onPoints(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg);
138-
139-
void onScenario(const tier4_planning_msgs::msg::Scenario::ConstSharedPtr msg);
140+
void set_current_pose();
140141

141142
void onTimer();
142143

@@ -170,8 +171,7 @@ class CostmapGenerator : public rclcpp::Node
170171

171172
/// \brief calculate cost from DynamicObjectArray
172173
/// \param[in] in_objects: subscribed DynamicObjectArray
173-
grid_map::Matrix generateObjectsCostmap(
174-
const autoware_perception_msgs::msg::PredictedObjects::ConstSharedPtr in_objects);
174+
grid_map::Matrix generateObjectsCostmap(const PredictedObjects::ConstSharedPtr in_objects);
175175

176176
/// \brief calculate cost from lanelet2 map
177177
grid_map::Matrix generatePrimitivesCostmap();
@@ -181,7 +181,9 @@ class CostmapGenerator : public rclcpp::Node
181181

182182
/// \brief measure processing time
183183
autoware::universe_utils::StopWatch<std::chrono::milliseconds> stop_watch;
184+
185+
friend class ::TestCostmapGenerator;
184186
};
185187
} // namespace autoware::costmap_generator
186188

187-
#endif // AUTOWARE_COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_
189+
#endif // AUTOWARE__COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_

planning/autoware_costmap_generator/include/autoware_costmap_generator/object_map_utils.hpp planning/autoware_costmap_generator/include/autoware/costmap_generator/utils/object_map_utils.hpp

+4-8
Original file line numberDiff line numberDiff line change
@@ -30,8 +30,8 @@
3030
*
3131
*/
3232

33-
#ifndef AUTOWARE_COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_
34-
#define AUTOWARE_COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_
33+
#ifndef AUTOWARE__COSTMAP_GENERATOR__UTILS__OBJECT_MAP_UTILS_HPP_
34+
#define AUTOWARE__COSTMAP_GENERATOR__UTILS__OBJECT_MAP_UTILS_HPP_
3535

3636
#include <grid_map_ros/grid_map_ros.hpp>
3737
#include <rclcpp/rclcpp.hpp>
@@ -55,16 +55,12 @@ namespace autoware::costmap_generator::object_map
5555
* @param[in] in_grid_layer_name Name to assign to the layer
5656
* @param[in] in_layer_background_value Empty state value
5757
* @param[in] in_fill_value Value to fill inside the given polygons
58-
* @param[in] in_tf_target_frame Target frame to transform the points
59-
* @param[in] in_tf_source_frame Source frame, where the points are located
60-
* @param[in] in_tf_listener Valid listener to obtain the transformation
6158
*/
6259
void fill_polygon_areas(
6360
grid_map::GridMap & out_grid_map, const std::vector<geometry_msgs::msg::Polygon> & in_polygons,
6461
const std::string & in_grid_layer_name, const float in_layer_background_value,
65-
const float in_fill_value, const std::string & in_tf_target_frame,
66-
const std::string & in_tf_source_frame, const tf2_ros::Buffer & in_tf_buffer);
62+
const float in_fill_value);
6763

6864
} // namespace autoware::costmap_generator::object_map
6965

70-
#endif // AUTOWARE_COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_
66+
#endif // AUTOWARE__COSTMAP_GENERATOR__UTILS__OBJECT_MAP_UTILS_HPP_

planning/autoware_costmap_generator/include/autoware_costmap_generator/objects_to_costmap.hpp planning/autoware_costmap_generator/include/autoware/costmap_generator/utils/objects_to_costmap.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -42,8 +42,8 @@
4242
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
4343
********************/
4444

45-
#ifndef AUTOWARE_COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_
46-
#define AUTOWARE_COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_
45+
#ifndef AUTOWARE__COSTMAP_GENERATOR__UTILS__OBJECTS_TO_COSTMAP_HPP_
46+
#define AUTOWARE__COSTMAP_GENERATOR__UTILS__OBJECTS_TO_COSTMAP_HPP_
4747

4848
#include <grid_map_ros/grid_map_ros.hpp>
4949

@@ -126,4 +126,4 @@ class ObjectsToCostmap
126126
grid_map::GridMap & objects_costmap);
127127
};
128128
} // namespace autoware::costmap_generator
129-
#endif // AUTOWARE_COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_
129+
#endif // AUTOWARE__COSTMAP_GENERATOR__UTILS__OBJECTS_TO_COSTMAP_HPP_

planning/autoware_costmap_generator/include/autoware_costmap_generator/points_to_costmap.hpp planning/autoware_costmap_generator/include/autoware/costmap_generator/utils/points_to_costmap.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -42,8 +42,8 @@
4242
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
4343
********************/
4444

45-
#ifndef AUTOWARE_COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_
46-
#define AUTOWARE_COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_
45+
#ifndef AUTOWARE__COSTMAP_GENERATOR__UTILS__POINTS_TO_COSTMAP_HPP_
46+
#define AUTOWARE__COSTMAP_GENERATOR__UTILS__POINTS_TO_COSTMAP_HPP_
4747

4848
#include <grid_map_ros/grid_map_ros.hpp>
4949

@@ -120,4 +120,4 @@ class PointsToCostmap
120120
};
121121
} // namespace autoware::costmap_generator
122122

123-
#endif // AUTOWARE_COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_
123+
#endif // AUTOWARE__COSTMAP_GENERATOR__UTILS__POINTS_TO_COSTMAP_HPP_

planning/autoware_costmap_generator/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
<depend>autoware_lanelet2_extension</depend>
2020
<depend>autoware_map_msgs</depend>
2121
<depend>autoware_perception_msgs</depend>
22+
<depend>autoware_test_utils</depend>
2223
<depend>autoware_universe_utils</depend>
2324
<depend>generate_parameter_library</depend>
2425
<depend>grid_map_ros</depend>

0 commit comments

Comments
 (0)