|
15 | 15 | #ifndef PARAMETERS_HPP_
|
16 | 16 | #define PARAMETERS_HPP_
|
17 | 17 |
|
18 |
| -#include "autoware/motion_utils/marker/marker_helper.hpp" |
19 |
| -#include "autoware/motion_utils/resample/resample.hpp" |
20 |
| -#include "autoware/motion_utils/trajectory/trajectory.hpp" |
21 |
| -#include "autoware/motion_velocity_planner_common/utils.hpp" |
22 |
| -#include "autoware/object_recognition_utils/predicted_path_utils.hpp" |
23 |
| -#include "autoware_utils/ros/parameter.hpp" |
24 |
| -#include "autoware_utils/ros/update_param.hpp" |
25 |
| -#include "autoware_utils/system/stop_watch.hpp" |
| 18 | +#include <autoware/motion_utils/marker/marker_helper.hpp> |
| 19 | +#include <autoware/motion_utils/resample/resample.hpp> |
| 20 | +#include <autoware/motion_utils/trajectory/trajectory.hpp> |
| 21 | +#include <autoware/motion_velocity_planner_common/utils.hpp> |
| 22 | +#include <autoware/object_recognition_utils/predicted_path_utils.hpp> |
| 23 | +#include <autoware_utils/ros/parameter.hpp> |
| 24 | +#include <autoware_utils/ros/update_param.hpp> |
| 25 | +#include <autoware_utils/system/stop_watch.hpp> |
26 | 26 | #include "type_alias.hpp"
|
27 | 27 | #include "types.hpp"
|
28 | 28 |
|
@@ -99,10 +99,11 @@ struct ObstacleFilteringParam
|
99 | 99 | double crossing_obstacle_collision_time_margin{};
|
100 | 100 |
|
101 | 101 | ObstacleFilteringParam() = default;
|
102 |
| - explicit ObstacleFilteringParam(rclcpp::Node & node) : inside_stop_object_types( |
103 |
| - utils::get_target_object_type(node, "obstacle_stop.obstacle_filtering.object_type.inside.")), |
| 102 | + explicit ObstacleFilteringParam(rclcpp::Node & node) |
| 103 | + : inside_stop_object_types( |
| 104 | + utils::get_target_object_type(node, "obstacle_stop.obstacle_filtering.object_type.inside.")), |
104 | 105 | outside_stop_object_types(
|
105 |
| - utils::get_target_object_type(node, "obstacle_stop.obstacle_filtering.object_type.outside.")) |
| 106 | + utils::get_target_object_type(node, "obstacle_stop.obstacle_filtering.object_type.outside.")) |
106 | 107 | {
|
107 | 108 | pointcloud_obstacle_filtering_param.pointcloud_voxel_grid_x = get_or_declare_parameter<double>(
|
108 | 109 | node, "obstacle_stop.obstacle_filtering.pointcloud.pointcloud_voxel_grid_x");
|
|
0 commit comments