Skip to content

Commit

Permalink
fix(behavior_velocity_planner): fix before/after line of virtual_traf…
Browse files Browse the repository at this point in the history
…fic_light

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
  • Loading branch information
kosuke55 committed Dec 28, 2021
1 parent ed3253c commit cf7c940
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,5 @@
ros__parameters:
virtual_traffic_light:
max_delay_sec: 3.0
near_line_distance: 1.0
check_timeout_after_stop_line: true
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,8 @@ class VirtualTrafficLightModule : public SceneModuleInterface
struct PlannerParam
{
double max_delay_sec;
double near_line_distance;
bool check_timeout_after_stop_line;
};

public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,9 @@ VirtualTrafficLightModuleManager::VirtualTrafficLightModuleManager(rclcpp::Node
{
auto & p = planner_param_;
p.max_delay_sec = node.declare_parameter(ns + ".max_delay_sec", 3.0);
p.near_line_distance = node.declare_parameter(ns + ".near_line_distance", 1.0);
p.check_timeout_after_stop_line =
node.declare_parameter(ns + ".check_timeout_after_stop_line", true);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -399,9 +399,9 @@ bool VirtualTrafficLightModule::modifyPathVelocity(
return true;
}

// Stop at stop_line if state is timeout before stop_line
if (isBeforeStopLine()) {
if (!isStateTimeout(*virtual_traffic_light_state)) {
// Stop at stop_line if state is timeout
if (isBeforeStopLine() || planner_param_.check_timeout_after_stop_line) {
if (isStateTimeout(*virtual_traffic_light_state)) {
RCLCPP_DEBUG(logger_, "state is timeout");
insertStopVelocityAtStopLine(path, stop_reason);
}
Expand Down Expand Up @@ -472,7 +472,7 @@ bool VirtualTrafficLightModule::isBeforeStopLine()
const auto signed_arc_length = tier4_autoware_utils::calcSignedArcLength(
module_data_.path.points, module_data_.head_pose.position, collision->point);

return signed_arc_length > 0;
return signed_arc_length > -planner_param_.near_line_distance;
}

bool VirtualTrafficLightModule::isAfterAnyEndLine()
Expand All @@ -493,8 +493,7 @@ bool VirtualTrafficLightModule::isAfterAnyEndLine()
const auto signed_arc_length = tier4_autoware_utils::calcSignedArcLength(
module_data_.path.points, module_data_.head_pose.position, collision->point);

constexpr double max_excess_distance = 3.0;
return signed_arc_length < -max_excess_distance;
return signed_arc_length < -planner_param_.near_line_distance;
}

bool VirtualTrafficLightModule::isNearAnyEndLine()
Expand All @@ -508,8 +507,7 @@ bool VirtualTrafficLightModule::isNearAnyEndLine()
const auto signed_arc_length = tier4_autoware_utils::calcSignedArcLength(
module_data_.path.points, module_data_.head_pose.position, collision->point);

constexpr double near_distance = 1.0;
return std::abs(signed_arc_length) < near_distance;
return std::abs(signed_arc_length) < planner_param_.near_line_distance;
}

boost::optional<tier4_v2x_msgs::msg::VirtualTrafficLightState>
Expand All @@ -535,10 +533,10 @@ bool VirtualTrafficLightModule::isStateTimeout(
const auto delay = (clock_->now() - rclcpp::Time(state.stamp)).seconds();
if (delay > planner_param_.max_delay_sec) {
RCLCPP_DEBUG(logger_, "delay=%f, max_delay=%f", delay, planner_param_.max_delay_sec);
return false;
return true;
}

return true;
return false;
}

bool VirtualTrafficLightModule::hasRightOfWay(
Expand Down

0 comments on commit cf7c940

Please sign in to comment.