Skip to content

Commit 1604474

Browse files
authored
refactor(goal_planner): initialize parameter with free function (autowarefoundation#8712)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent abcf3ee commit 1604474

File tree

2 files changed

+23
-17
lines changed
  • planning/behavior_path_planner/autoware_behavior_path_goal_planner_module

2 files changed

+23
-17
lines changed

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,9 @@ namespace autoware::behavior_path_planner
2929

3030
class GoalPlannerModuleManager : public SceneModuleManagerInterface
3131
{
32+
static GoalPlannerParameters initGoalPlannerParameters(
33+
rclcpp::Node * node, const std::string & base_ns);
34+
3235
public:
3336
GoalPlannerModuleManager() : SceneModuleManagerInterface{"goal_planner"} {}
3437

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp

+20-17
Original file line numberDiff line numberDiff line change
@@ -25,14 +25,11 @@
2525

2626
namespace autoware::behavior_path_planner
2727
{
28-
void GoalPlannerModuleManager::init(rclcpp::Node * node)
29-
{
30-
// init manager interface
31-
initInterface(node, {""});
3228

29+
GoalPlannerParameters GoalPlannerModuleManager::initGoalPlannerParameters(
30+
rclcpp::Node * node, const std::string & base_ns)
31+
{
3332
GoalPlannerParameters p;
34-
35-
const std::string base_ns = "goal_planner.";
3633
// general params
3734
{
3835
p.th_stopped_velocity = node->declare_parameter<double>(base_ns + "th_stopped_velocity");
@@ -71,7 +68,7 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node)
7168
p.parking_policy = ParkingPolicy::RIGHT_SIDE;
7269
} else {
7370
RCLCPP_ERROR_STREAM(
74-
node->get_logger().get_child(name()),
71+
node->get_logger(),
7572
"[goal_planner] invalid parking_policy: " << parking_policy_name << std::endl);
7673
exit(EXIT_FAILURE);
7774
}
@@ -115,7 +112,7 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node)
115112
p.object_recognition_collision_check_soft_margins.empty() ||
116113
p.object_recognition_collision_check_hard_margins.empty()) {
117114
RCLCPP_FATAL_STREAM(
118-
node->get_logger().get_child(name()),
115+
node->get_logger(),
119116
"object_recognition.collision_check_soft_margins and "
120117
<< "object_recognition.collision_check_hard_margins must not be empty. "
121118
<< "Terminating the program...");
@@ -400,22 +397,28 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node)
400397
// validation of parameters
401398
if (p.shift_sampling_num < 1) {
402399
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...");
407403
exit(EXIT_FAILURE);
408404
}
409405
if (p.maximum_deceleration < 0.0) {
410406
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...");
415410
exit(EXIT_FAILURE);
416411
}
412+
return p;
413+
}
417414

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));
419422
}
420423

421424
void GoalPlannerModuleManager::updateModuleParams(

0 commit comments

Comments
 (0)