Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(behavior_path_planner): change turn signal output timing #2493

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
36 changes: 19 additions & 17 deletions planning/behavior_path_planner/src/behavior_path_planner_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -627,23 +627,6 @@ void BehaviorPathPlannerNode::run()

// update planner data
planner_data_->prev_output_path = path;
mutex_pd_.unlock();

// publish drivable bounds
publish_bounds(*path);

const size_t target_idx = findEgoIndex(path->points);
util::clipPathLength(*path, target_idx, planner_data_->parameters);

if (!path->points.empty()) {
path_publisher_->publish(*path);
} else {
RCLCPP_ERROR_THROTTLE(
get_logger(), *get_clock(), 5000, "behavior path output is empty! Stop publish.");
}

const auto path_candidate = getPathCandidate(output, planner_data);
path_candidate_publisher_->publish(util::toPath(*path_candidate));

// for turn signal
{
Expand All @@ -665,6 +648,25 @@ void BehaviorPathPlannerNode::run()
publish_steering_factor(turn_signal);
}

// unlock planner data
mutex_pd_.unlock();

// publish drivable bounds
publish_bounds(*path);

const size_t target_idx = findEgoIndex(path->points);
util::clipPathLength(*path, target_idx, planner_data_->parameters);

if (!path->points.empty()) {
path_publisher_->publish(*path);
} else {
RCLCPP_ERROR_THROTTLE(
get_logger(), *get_clock(), 5000, "behavior path output is empty! Stop publish.");
}

const auto path_candidate = getPathCandidate(output, planner_data);
path_candidate_publisher_->publish(util::toPath(*path_candidate));

publishSceneModuleDebugMsg();

if (planner_data->parameters.visualize_drivable_area_for_shared_linestrings_lanelet) {
Expand Down