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

fix(behavior_path): only apply spline interpolation for its output, not for turn_signal processing #909

Merged
merged 6 commits into from
Oct 10, 2023
Merged
Show file tree
Hide file tree
Changes from 4 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
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,8 @@ class BehaviorPathPlannerNode : public rclcpp::Node
/**
* @brief extract path from behavior tree output
*/
PathWithLaneId::SharedPtr getPath(const BehaviorModuleOutput & bt_out);
std::pair<PathWithLaneId::SharedPtr, PathWithLaneId::SharedPtr> getPath(
const BehaviorModuleOutput & bt_out);

/**
* @brief extract path candidate from behavior tree output
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -478,7 +478,10 @@ void BehaviorPathPlannerNode::run()
const auto output = bt_manager_->run(planner_data_);

// path handling
const auto path = getPath(output);
const auto paths = getPath(output);
const auto path = paths.first;
const auto original_path = paths.second;

const auto path_candidate = getPathCandidate(output);
planner_data_->prev_output_path = path;

Expand All @@ -504,7 +507,7 @@ void BehaviorPathPlannerNode::run()
hazard_signal.command = output.turn_signal_info.hazard_signal.command;
} else {
turn_signal = turn_signal_decider_.getTurnSignal(
*path, planner_data_->self_pose->pose, *(planner_data_->route_handler),
*original_path, planner_data_->self_pose->pose, *(planner_data_->route_handler),
output.turn_signal_info.turn_signal, output.turn_signal_info.signal_distance);
hazard_signal.command = HazardLightsCommand::DISABLE;
}
Expand All @@ -527,7 +530,9 @@ void BehaviorPathPlannerNode::run()
RCLCPP_DEBUG(get_logger(), "----- behavior path planner end -----\n\n");
}

PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath(const BehaviorModuleOutput & bt_output)
// output: spline interpolated path, original path
std::pair<PathWithLaneId::SharedPtr, PathWithLaneId::SharedPtr> BehaviorPathPlannerNode::getPath(
const BehaviorModuleOutput & bt_output)
{
// TODO(Horibe) do some error handling when path is not available.

Expand All @@ -539,7 +544,7 @@ PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath(const BehaviorModuleO

const auto resampled_path =
util::resamplePathWithSpline(*path, planner_data_->parameters.path_interval);
return std::make_shared<PathWithLaneId>(resampled_path);
return std::make_pair(std::make_shared<PathWithLaneId>(resampled_path), path);
}

PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPathCandidate(
Expand Down
Loading