diff --git a/control/predicted_path_checker/config/predicted_path_checker.param.yaml b/control/predicted_path_checker/config/predicted_path_checker.param.yaml index 5988875c8bd6d..23eea4b752b9a 100644 --- a/control/predicted_path_checker/config/predicted_path_checker.param.yaml +++ b/control/predicted_path_checker/config/predicted_path_checker.param.yaml @@ -14,4 +14,3 @@ longitudinal_margin: 0.15 stop_search_radius: 4.0 resample_interval: 0.3 - diff --git a/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp b/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp index 8520cdcd71d74..389c24b76d653 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp +++ b/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COLLISION_CHECKER__COLLISION_CHECKER_HPP_ -#define COLLISION_CHECKER__COLLISION_CHECKER_HPP_ +#ifndef PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ +#define PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ #include #include @@ -117,4 +117,4 @@ class CollisionChecker }; } // namespace collision_checker -#endif // COLLISION_CHECKER__COLLISION_CHECKER_HPP_ +#endif // PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ diff --git a/control/predicted_path_checker/package.xml b/control/predicted_path_checker/package.xml index fd8e02315da9f..198bb053abe55 100644 --- a/control/predicted_path_checker/package.xml +++ b/control/predicted_path_checker/package.xml @@ -14,12 +14,12 @@ autoware_auto_planning_msgs boost diagnostic_updater - motion_utils eigen geometry_msgs + motion_utils nav_msgs - pcl_ros pcl_conversions + pcl_ros rclcpp rclcpp_components sensor_msgs diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp index 0b2a33cb207d9..e32105a23ea10 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp +++ b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp @@ -41,12 +41,18 @@ PredictedPathCheckerNode::PredictedPathCheckerNode(const rclcpp::NodeOptions & n node_param_.delay_time = declare_parameter("delay_time", 0.5); // Collision Checker Parameter - collision_checker_param_.stop_search_radius = declare_parameter("collision_checker_params.stop_search_radius", 5.0); - collision_checker_param_.longitudinal_margin = declare_parameter("collision_checker_params.longitudinal_margin", 0.15); - collision_checker_param_.width_margin = declare_parameter("collision_checker_params.width_margin", 0.2); - collision_checker_param_.stop_margin = declare_parameter("collision_checker_params.stop_margin", 1.0); - collision_checker_param_.search_radius = declare_parameter("collision_checker_params.search_radius", 6.0); - collision_checker_param_.resample_interval = declare_parameter("collision_checker_params.resample_interval", 0.5); + collision_checker_param_.stop_search_radius = + declare_parameter("collision_checker_params.stop_search_radius", 5.0); + collision_checker_param_.longitudinal_margin = + declare_parameter("collision_checker_params.longitudinal_margin", 0.15); + collision_checker_param_.width_margin = + declare_parameter("collision_checker_params.width_margin", 0.2); + collision_checker_param_.stop_margin = + declare_parameter("collision_checker_params.stop_margin", 1.0); + collision_checker_param_.search_radius = + declare_parameter("collision_checker_params.search_radius", 6.0); + collision_checker_param_.resample_interval = + declare_parameter("collision_checker_params.resample_interval", 0.5); vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo();