Skip to content

Commit 804f8f8

Browse files
Using the Warn params is bugged, wont fix
Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent 3bb9441 commit 804f8f8

File tree

1 file changed

+0
-60
lines changed
  • planning/behavior_path_goal_planner_module/src

1 file changed

+0
-60
lines changed

planning/behavior_path_goal_planner_module/src/manager.cpp

-60
Original file line numberDiff line numberDiff line change
@@ -456,18 +456,6 @@ void GoalPlannerModuleManager::updateModuleParams(
456456
updateParam<double>(
457457
parameters, ns + "ignore_distance_from_lane_start", p->ignore_distance_from_lane_start);
458458
updateParam<double>(parameters, ns + "margin_from_boundary", p->margin_from_boundary);
459-
460-
std::string parking_policy_name;
461-
updateParam<std::string>(parameters, ns + "parking_policy", parking_policy_name);
462-
if (parking_policy_name == "left_side") {
463-
p->parking_policy = ParkingPolicy::LEFT_SIDE;
464-
} else if (parking_policy_name == "right_side") {
465-
p->parking_policy = ParkingPolicy::RIGHT_SIDE;
466-
} else {
467-
RCLCPP_WARN_STREAM(
468-
node_->get_logger().get_child(name()),
469-
"[goal_planner] invalid parking_policy: " << parking_policy_name << std::endl);
470-
}
471459
}
472460

473461
// occupancy grid map
@@ -500,30 +488,6 @@ void GoalPlannerModuleManager::updateModuleParams(
500488
updateParam(parameters, ns + "detection_bound_offset", p->detection_bound_offset);
501489
updateParam(parameters, ns + "outer_road_detection_offset", p->outer_road_detection_offset);
502490
updateParam(parameters, ns + "inner_road_detection_offset", p->inner_road_detection_offset);
503-
504-
std::vector<double> temp_object_recognition_collision_check_soft_margins;
505-
std::vector<double> temp_object_recognition_collision_check_hard_margins;
506-
updateParam<std::vector<double>>(
507-
parameters, ns + "collision_check_soft_margins",
508-
temp_object_recognition_collision_check_soft_margins);
509-
updateParam<std::vector<double>>(
510-
parameters, ns + "collision_check_hard_margins",
511-
temp_object_recognition_collision_check_hard_margins);
512-
513-
// validate object recognition collision check margins
514-
if (
515-
temp_object_recognition_collision_check_soft_margins.empty() ||
516-
temp_object_recognition_collision_check_hard_margins.empty()) {
517-
RCLCPP_WARN_STREAM(
518-
node_->get_logger().get_child(name()),
519-
"object_recognition.collision_check_soft_margins and "
520-
<< "object_recognition.collision_check_hard_margins must not be empty. " << std::endl);
521-
} else {
522-
p->object_recognition_collision_check_soft_margins =
523-
temp_object_recognition_collision_check_soft_margins;
524-
p->object_recognition_collision_check_hard_margins =
525-
temp_object_recognition_collision_check_hard_margins;
526-
}
527491
}
528492

529493
// pull over general params
@@ -536,37 +500,13 @@ void GoalPlannerModuleManager::updateModuleParams(
536500
updateParam<double>(
537501
parameters, ns + "pull_over_minimum_velocity", p->pull_over_minimum_velocity);
538502
updateParam<double>(parameters, ns + "decide_path_distance", p->decide_path_distance);
539-
540-
double temp_maximum_deceleration;
541-
updateParam<double>(parameters, ns + "maximum_deceleration", temp_maximum_deceleration);
542-
if (temp_maximum_deceleration < 0.0) {
543-
RCLCPP_WARN_STREAM(
544-
node_->get_logger().get_child(name()),
545-
"maximum_deceleration cannot be negative value. Given parameter: "
546-
<< temp_maximum_deceleration << std::endl);
547-
} else {
548-
p->maximum_deceleration = temp_maximum_deceleration;
549-
}
550-
551503
updateParam<double>(parameters, ns + "maximum_jerk", p->maximum_jerk);
552504
}
553505

554506
// shift parking
555507
{
556508
const std::string ns = base_ns + "pull_over.shift_parking.";
557509
updateParam<bool>(parameters, ns + "enable_shift_parking", p->enable_shift_parking);
558-
int temp_shift_sampling_num;
559-
updateParam<int>(parameters, ns + "shift_sampling_num", temp_shift_sampling_num);
560-
// validation of parameters
561-
if (temp_shift_sampling_num < 1) {
562-
RCLCPP_WARN_STREAM(
563-
node_->get_logger().get_child(name()),
564-
"shift_sampling_num must be positive integer. Given parameter: " << temp_shift_sampling_num
565-
<< std::endl);
566-
} else {
567-
p->shift_sampling_num = temp_shift_sampling_num;
568-
}
569-
570510
updateParam<double>(parameters, ns + "maximum_lateral_jerk", p->maximum_lateral_jerk);
571511
updateParam<double>(parameters, ns + "minimum_lateral_jerk", p->minimum_lateral_jerk);
572512
updateParam<double>(parameters, ns + "deceleration_interval", p->deceleration_interval);

0 commit comments

Comments
 (0)