|
25 | 25 |
|
26 | 26 | namespace autoware::behavior_path_planner
|
27 | 27 | {
|
28 |
| -void GoalPlannerModuleManager::init(rclcpp::Node * node) |
29 |
| -{ |
30 |
| - // init manager interface |
31 |
| - initInterface(node, {""}); |
32 | 28 |
|
| 29 | +GoalPlannerParameters GoalPlannerModuleManager::initGoalPlannerParameters( |
| 30 | + rclcpp::Node * node, const std::string & base_ns) |
| 31 | +{ |
33 | 32 | GoalPlannerParameters p;
|
34 |
| - |
35 |
| - const std::string base_ns = "goal_planner."; |
36 | 33 | // general params
|
37 | 34 | {
|
38 | 35 | p.th_stopped_velocity = node->declare_parameter<double>(base_ns + "th_stopped_velocity");
|
@@ -71,7 +68,7 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node)
|
71 | 68 | p.parking_policy = ParkingPolicy::RIGHT_SIDE;
|
72 | 69 | } else {
|
73 | 70 | RCLCPP_ERROR_STREAM(
|
74 |
| - node->get_logger().get_child(name()), |
| 71 | + node->get_logger(), |
75 | 72 | "[goal_planner] invalid parking_policy: " << parking_policy_name << std::endl);
|
76 | 73 | exit(EXIT_FAILURE);
|
77 | 74 | }
|
@@ -115,7 +112,7 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node)
|
115 | 112 | p.object_recognition_collision_check_soft_margins.empty() ||
|
116 | 113 | p.object_recognition_collision_check_hard_margins.empty()) {
|
117 | 114 | RCLCPP_FATAL_STREAM(
|
118 |
| - node->get_logger().get_child(name()), |
| 115 | + node->get_logger(), |
119 | 116 | "object_recognition.collision_check_soft_margins and "
|
120 | 117 | << "object_recognition.collision_check_hard_margins must not be empty. "
|
121 | 118 | << "Terminating the program...");
|
@@ -400,22 +397,28 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node)
|
400 | 397 | // validation of parameters
|
401 | 398 | if (p.shift_sampling_num < 1) {
|
402 | 399 | RCLCPP_FATAL_STREAM(
|
403 |
| - node->get_logger().get_child(name()), |
404 |
| - "shift_sampling_num must be positive integer. Given parameter: " |
405 |
| - << p.shift_sampling_num << std::endl |
406 |
| - << "Terminating the program..."); |
| 400 | + node->get_logger(), "shift_sampling_num must be positive integer. Given parameter: " |
| 401 | + << p.shift_sampling_num << std::endl |
| 402 | + << "Terminating the program..."); |
407 | 403 | exit(EXIT_FAILURE);
|
408 | 404 | }
|
409 | 405 | if (p.maximum_deceleration < 0.0) {
|
410 | 406 | RCLCPP_FATAL_STREAM(
|
411 |
| - node->get_logger().get_child(name()), |
412 |
| - "maximum_deceleration cannot be negative value. Given parameter: " |
413 |
| - << p.maximum_deceleration << std::endl |
414 |
| - << "Terminating the program..."); |
| 407 | + node->get_logger(), "maximum_deceleration cannot be negative value. Given parameter: " |
| 408 | + << p.maximum_deceleration << std::endl |
| 409 | + << "Terminating the program..."); |
415 | 410 | exit(EXIT_FAILURE);
|
416 | 411 | }
|
| 412 | + return p; |
| 413 | +} |
417 | 414 |
|
418 |
| - parameters_ = std::make_shared<GoalPlannerParameters>(p); |
| 415 | +void GoalPlannerModuleManager::init(rclcpp::Node * node) |
| 416 | +{ |
| 417 | + // init manager interface |
| 418 | + initInterface(node, {""}); |
| 419 | + |
| 420 | + const std::string base_ns = "goal_planner."; |
| 421 | + parameters_ = std::make_shared<GoalPlannerParameters>(initGoalPlannerParameters(node, base_ns)); |
419 | 422 | }
|
420 | 423 |
|
421 | 424 | void GoalPlannerModuleManager::updateModuleParams(
|
|
0 commit comments