Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit ccf2a11

Browse files
committedFeb 16, 2024
fix(lane_change): fix dynamic reconfigure and add parameters
Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent 32073c0 commit ccf2a11

File tree

1 file changed

+98
-3
lines changed
  • planning/behavior_path_lane_change_module/src

1 file changed

+98
-3
lines changed
 

‎planning/behavior_path_lane_change_module/src/manager.cpp

+98-3
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include "tier4_autoware_utils/ros/parameter.hpp"
1919
#include "tier4_autoware_utils/ros/update_param.hpp"
2020

21+
#include <rclcpp/logging.hpp>
2122
#include <rclcpp/rclcpp.hpp>
2223

2324
#include <memory>
@@ -279,10 +280,104 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector<rclcpp::Param
279280

280281
auto p = parameters_;
281282

282-
const std::string ns = name_ + ".";
283-
updateParam<double>(
284-
parameters, ns + "finish_judge_lateral_threshold", p->finish_judge_lateral_threshold);
283+
{
284+
const std::string ns = "lane_change.";
285+
updateParam<double>(parameters, ns + "backward_lane_length", p->backward_lane_length);
286+
updateParam<double>(parameters, ns + "prepare_duration", p->lane_change_prepare_duration);
287+
288+
updateParam<double>(
289+
parameters, ns + "backward_length_buffer_for_end_of_lane",
290+
p->backward_length_buffer_for_end_of_lane);
291+
updateParam<double>(
292+
parameters, ns + "backward_length_buffer_for_blocking_object",
293+
p->backward_length_buffer_for_blocking_object);
294+
updateParam<double>(
295+
parameters, ns + "lane_change_finish_judge_buffer", p->lane_change_finish_judge_buffer);
296+
297+
updateParam<double>(
298+
parameters, ns + "lane_changing_lateral_jerk", p->lane_changing_lateral_jerk);
299+
300+
updateParam<double>(
301+
parameters, ns + "minimum_lane_changing_velocity", p->minimum_lane_changing_velocity);
302+
updateParam<double>(
303+
parameters, ns + "prediction_time_resolution", p->prediction_time_resolution);
304+
305+
int longitudinal_acc_sampling_num = 0;
306+
updateParam<int>(
307+
parameters, ns + "longitudinal_acceleration_sampling_num", longitudinal_acc_sampling_num);
308+
if (longitudinal_acc_sampling_num > 0) {
309+
p->longitudinal_acc_sampling_num = longitudinal_acc_sampling_num;
310+
}
311+
312+
int lateral_acc_sampling_num = 0;
313+
updateParam<int>(
314+
parameters, ns + "lateral_acceleration_sampling_num", lateral_acc_sampling_num);
315+
if (lateral_acc_sampling_num > 0) {
316+
p->lateral_acc_sampling_num = lateral_acc_sampling_num;
317+
}
318+
319+
updateParam<double>(
320+
parameters, ns + "finish_judge_lateral_threshold", p->finish_judge_lateral_threshold);
321+
updateParam<bool>(parameters, ns + "publish_debug_marker", p->publish_debug_marker);
322+
323+
// longitudinal acceleration
324+
updateParam<double>(parameters, ns + "min_longitudinal_acc", p->min_longitudinal_acc);
325+
updateParam<double>(parameters, ns + "max_longitudinal_acc", p->max_longitudinal_acc);
326+
}
327+
328+
{
329+
const std::string ns = "lane_change.safety_check.lane_expansion.";
330+
updateParam<double>(parameters, ns + "left_offset", p->lane_expansion_left_offset);
331+
updateParam<double>(parameters, ns + "right_offset", p->lane_expansion_right_offset);
332+
}
333+
334+
{
335+
const std::string ns = "lane_change.target_object.";
336+
updateParam<bool>(parameters, ns + "car", p->object_types_to_check.check_car);
337+
updateParam<bool>(parameters, ns + "truck", p->object_types_to_check.check_truck);
338+
updateParam<bool>(parameters, ns + "bus", p->object_types_to_check.check_bus);
339+
updateParam<bool>(parameters, ns + "trailer", p->object_types_to_check.check_trailer);
340+
updateParam<bool>(parameters, ns + "unknown", p->object_types_to_check.check_unknown);
341+
updateParam<bool>(parameters, ns + "bicycle", p->object_types_to_check.check_bicycle);
342+
updateParam<bool>(parameters, ns + "motorcycle", p->object_types_to_check.check_motorcycle);
343+
updateParam<bool>(parameters, ns + "pedestrian", p->object_types_to_check.check_pedestrian);
344+
}
345+
346+
{
347+
const std::string ns = "lane_change.regulation.";
348+
updateParam<bool>(parameters, ns + "crosswalk", p->regulate_on_crosswalk);
349+
updateParam<bool>(parameters, ns + "intersection", p->regulate_on_intersection);
350+
updateParam<bool>(parameters, ns + "traffic_light", p->regulate_on_traffic_light);
351+
}
352+
353+
{
354+
const std::string ns = "lane_change.stuck_detection.";
355+
updateParam<double>(parameters, ns + "velocity", p->stop_velocity_threshold);
356+
updateParam<double>(parameters, ns + "stop_time", p->stop_time_threshold);
357+
}
285358

359+
{
360+
const std::string ns = "lane_change.cancel.";
361+
bool enable_on_prepare_phase = true;
362+
updateParam<bool>(parameters, ns + "enable_on_prepare_phase", enable_on_prepare_phase);
363+
if (!enable_on_prepare_phase) {
364+
RCLCPP_WARN_ONCE(node_->get_logger(), "WARNING! Lane Change cancel function is disabled.");
365+
p->cancel.enable_on_prepare_phase = enable_on_prepare_phase;
366+
}
367+
368+
bool enable_on_lane_changing_phase = true;
369+
updateParam<bool>(
370+
parameters, ns + "enable_on_lane_changing_phase", enable_on_lane_changing_phase);
371+
if (!enable_on_lane_changing_phase) {
372+
RCLCPP_WARN_ONCE(node_->get_logger(), "WARNING! Lane Change abort function is disabled.");
373+
p->cancel.enable_on_lane_changing_phase = enable_on_lane_changing_phase;
374+
}
375+
376+
updateParam<double>(parameters, ns + "delta_time", p->cancel.delta_time);
377+
updateParam<double>(parameters, ns + "duration", p->cancel.duration);
378+
updateParam<double>(parameters, ns + "max_lateral_jerk", p->cancel.max_lateral_jerk);
379+
updateParam<double>(parameters, ns + "overhang_tolerance", p->cancel.overhang_tolerance);
380+
}
286381
std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) {
287382
if (!observer.expired()) observer.lock()->updateModuleParams(p);
288383
});

0 commit comments

Comments
 (0)
Please sign in to comment.