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(autoware_behavior_velocity_traffic_light_module): add v2i to behavior_velocity_traffic_light #1774

Open
wants to merge 10 commits into
base: awf-latest
Choose a base branch
from
Open
1 change: 0 additions & 1 deletion .github/sync-files.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
- source: .github/workflows/comment-on-pr.yaml
- source: .github/workflows/delete-closed-pr-docs.yaml
- source: .github/workflows/deploy-docs.yaml
- source: .github/workflows/github-release.yaml
yhisaki marked this conversation as resolved.
Show resolved Hide resolved
- source: .github/workflows/pre-commit.yaml
- source: .github/workflows/pre-commit-optional.yaml
- source: .github/workflows/pre-commit-optional-autoupdate.yaml
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,3 +7,9 @@
yellow_lamp_period: 2.75
enable_pass_judge: true
enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval

v2i:
use_rest_time: false
last_time_allowed_to_pass: 2.0 # relative time against at the time of turn to red
velocity_threshold: 0.5 # change the decision logic whether the current velocity is faster or not
required_time_to_departure: 3.0 # prevent low speed pass
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
<depend>autoware_universe_utils</depend>
<depend>eigen</depend>
<depend>geometry_msgs</depend>
<depend>jpn_signal_v2i_msgs</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>tf2</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,14 +17,17 @@
#include <autoware/behavior_velocity_planner_common/utilization/util.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <autoware/universe_utils/ros/parameter.hpp>
#include <rclcpp/logging.hpp>

#include <tf2/utils.h>

#include <limits>
#include <memory>
#include <optional>
#include <set>
#include <string>
#include <utility>
#include <vector>
namespace autoware::behavior_velocity_planner
{
using autoware::universe_utils::getOrDeclareParameter;
Expand All @@ -42,8 +45,22 @@ TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node)
planner_param_.enable_pass_judge = getOrDeclareParameter<bool>(node, ns + ".enable_pass_judge");
planner_param_.yellow_lamp_period =
getOrDeclareParameter<double>(node, ns + ".yellow_lamp_period");
planner_param_.v2i_use_rest_time = getOrDeclareParameter<bool>(node, ns + ".v2i.use_rest_time");
planner_param_.v2i_last_time_allowed_to_pass =
getOrDeclareParameter<double>(node, ns + ".v2i.last_time_allowed_to_pass");
planner_param_.v2i_velocity_threshold =
getOrDeclareParameter<double>(node, ns + ".v2i.velocity_threshold");
planner_param_.v2i_required_time_to_departure =
getOrDeclareParameter<double>(node, ns + ".v2i.required_time_to_departure");
pub_tl_state_ = node.create_publisher<autoware_perception_msgs::msg::TrafficLightGroup>(
"~/output/traffic_signal", 1);

if (planner_param_.v2i_use_rest_time) {
RCLCPP_INFO(logger_, "V2I is enabled");
v2i_subscriber_ = autoware::universe_utils::InterProcessPollingSubscriber<
jpn_signal_v2i_msgs::msg::TrafficLightInfo>::
create_subscription(&node, "/v2i/external/v2i_traffic_light_info", 1);
}
}

void TrafficLightModuleManager::modifyPathVelocity(tier4_planning_msgs::msg::PathWithLaneId * path)
Expand All @@ -53,6 +70,8 @@ void TrafficLightModuleManager::modifyPathVelocity(tier4_planning_msgs::msg::Pat

autoware_perception_msgs::msg::TrafficLightGroup tl_state;

if (planner_param_.v2i_use_rest_time) updateV2IRestTimeInfo();

nearest_ref_stop_path_point_index_ = static_cast<int>(path->points.size() - 1);
for (const auto & scene_module : scene_modules_) {
std::shared_ptr<TrafficLightModule> traffic_light_scene_module(
Expand Down Expand Up @@ -103,6 +122,9 @@ void TrafficLightModuleManager::launchNewModules(
registerModule(std::make_shared<TrafficLightModule>(
lane_id, *(traffic_light_reg_elem.first), traffic_light_reg_elem.second, planner_param_,
logger_.get_child("traffic_light_module"), clock_, time_keeper_,
std::bind(
&TrafficLightModuleManager::getV2IRestTimeToRedSignal, this,
traffic_light_reg_elem.first->id()),
planning_factor_interface_));
generateUUID(lane_id);
updateRTCStatus(
Expand Down Expand Up @@ -163,6 +185,37 @@ bool TrafficLightModuleManager::hasSameTrafficLight(
return false;
}

void TrafficLightModuleManager::updateV2IRestTimeInfo()
{
if (!v2i_subscriber_) {
return;
}
auto msg = v2i_subscriber_->takeData();
if (!msg) {
return;
}

std::vector<lanelet::Id> traffic_light_ids;
traffic_light_id_to_rest_time_map_.clear();
for (const auto & car_light : msg->car_lights) {
for (const auto & state : car_light.states) {
traffic_light_id_to_rest_time_map_[state.traffic_light_group_id] = {
msg->header.stamp, car_light.min_rest_time_to_red};
traffic_light_ids.push_back(state.traffic_light_group_id);
}
}
}

std::optional<TrafficSignalTimeToRedStamped> TrafficLightModuleManager::getV2IRestTimeToRedSignal(
const lanelet::Id & id) const
{
const auto rest_time_to_red_signal = traffic_light_id_to_rest_time_map_.find(id);
if (rest_time_to_red_signal == traffic_light_id_to_rest_time_map_.end()) {
return std::nullopt;
}
return rest_time_to_red_signal->second;
}

} // namespace autoware::behavior_velocity_planner

#include <pluginlib/class_list_macros.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,14 @@
#include <autoware/behavior_velocity_planner_common/plugin_interface.hpp>
#include <autoware/behavior_velocity_planner_common/plugin_wrapper.hpp>
#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
#include <autoware/universe_utils/ros/polling_subscriber.hpp>
#include <rclcpp/rclcpp.hpp>

#include <jpn_signal_v2i_msgs/msg/traffic_light_info.hpp>
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>

#include <functional>
#include <map>
#include <memory>
#include <optional>

Expand Down Expand Up @@ -55,6 +58,16 @@ class TrafficLightModuleManager : public SceneModuleManagerInterfaceWithRTC
const lanelet::TrafficLightConstPtr element,
const lanelet::TrafficLightConstPtr registered_element) const;

void updateV2IRestTimeInfo();

std::optional<TrafficSignalTimeToRedStamped> getV2IRestTimeToRedSignal(
const lanelet::Id & id) const;

// V2I
autoware::universe_utils::InterProcessPollingSubscriber<
jpn_signal_v2i_msgs::msg::TrafficLightInfo>::SharedPtr v2i_subscriber_;
std::map<lanelet::Id, TrafficSignalTimeToRedStamped> traffic_light_id_to_rest_time_map_;

// Debug
rclcpp::Publisher<autoware_perception_msgs::msg::TrafficLightGroup>::SharedPtr pub_tl_state_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,17 @@
#include <autoware/behavior_velocity_planner_common/utilization/util.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <autoware/traffic_light_utils/traffic_light_utils.hpp>
#include <rclcpp/clock.hpp>
#include <rclcpp/logging.hpp>

#include <boost/geometry/algorithms/distance.hpp>
#include <boost/geometry/algorithms/intersection.hpp>

#include <tf2/utils.h>

#include <ctime>
#include <memory>
#include <optional>

#ifdef ROS_DISTRO_GALACTIC
#include <tf2_eigen/tf2_eigen.h>
Expand All @@ -45,6 +49,8 @@ TrafficLightModule::TrafficLightModule(
lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger,
const rclcpp::Clock::SharedPtr clock,
const std::shared_ptr<universe_utils::TimeKeeper> time_keeper,
const std::function<std::optional<TrafficSignalTimeToRedStamped>(void)> &
get_rest_time_to_red_signal,
const std::shared_ptr<planning_factor_interface::PlanningFactorInterface>
planning_factor_interface)
: SceneModuleInterfaceWithRTC(lane_id, logger, clock, time_keeper, planning_factor_interface),
Expand All @@ -53,7 +59,8 @@ TrafficLightModule::TrafficLightModule(
lane_(lane),
state_(State::APPROACH),
debug_data_(),
is_prev_state_stop_(false)
is_prev_state_stop_(false),
get_rest_time_to_red_signal_(get_rest_time_to_red_signal)
{
planner_param_ = planner_param;
}
Expand Down Expand Up @@ -107,6 +114,16 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path)

first_ref_stop_path_point_index_ = stop_line.value().first;

// Use V2I if available
if (planner_param_.v2i_use_rest_time) {
bool is_v2i_handled = handleV2I(signed_arc_length_to_stop_point, [&]() {
*path = insertStopPose(input_path, stop_line.value().first, stop_line.value().second);
});
if (is_v2i_handled) {
return true;
}
}

// Check if stop is coming.
const bool is_stop_signal = isStopSignal();

Expand Down Expand Up @@ -302,4 +319,42 @@ tier4_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertStopPose(
return modified_path;
}

bool TrafficLightModule::handleV2I(
const double & signed_arc_length_to_stop_point, const std::function<void()> & insert_stop_pose)
{
std::optional<TrafficSignalTimeToRedStamped> rest_time_to_red_signal =
get_rest_time_to_red_signal_();

if (!rest_time_to_red_signal) {
RCLCPP_WARN_THROTTLE(
logger_, *clock_, 5000,
"Failed to get V2I rest time to red signal. traffic_light_lane_id: %ld", lane_id_);
return false;
}

auto time_diff = (clock_->now() - rest_time_to_red_signal->stamp).seconds();
if (time_diff > planner_param_.tl_state_timeout) {
RCLCPP_WARN_THROTTLE(
logger_, *clock_, 5000, "V2I data is timeout. traffic_light_lane_id: %ld, time diff: %f",
lane_id_, time_diff);
return false;
}

const double rest_time_allowed_to_go_ahead =
rest_time_to_red_signal->time_to_red - planner_param_.v2i_last_time_allowed_to_pass;
const double ego_v = planner_data_->current_velocity->twist.linear.x;

const bool should_stop =
(ego_v >= planner_param_.v2i_velocity_threshold &&
ego_v * rest_time_allowed_to_go_ahead <= signed_arc_length_to_stop_point) ||
(ego_v < planner_param_.v2i_velocity_threshold &&
rest_time_allowed_to_go_ahead < planner_param_.v2i_required_time_to_departure);

setSafe(!should_stop);
if (isActivated()) {
return true;
}
insert_stop_pose();
return true;
}
} // namespace autoware::behavior_velocity_planner
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef SCENE_HPP_
#define SCENE_HPP_

#include <functional>
#include <memory>
#include <optional>
#include <tuple>
Expand All @@ -33,6 +34,13 @@

namespace autoware::behavior_velocity_planner
{

struct TrafficSignalTimeToRedStamped
{
builtin_interfaces::msg::Time stamp;
double time_to_red{};
};

class TrafficLightModule : public SceneModuleInterfaceWithRTC
{
public:
Expand Down Expand Up @@ -63,6 +71,11 @@ class TrafficLightModule : public SceneModuleInterfaceWithRTC
double yellow_lamp_period;
double stop_time_hysteresis;
bool enable_pass_judge;
// V2I Parameter
bool v2i_use_rest_time;
double v2i_last_time_allowed_to_pass;
double v2i_velocity_threshold;
double v2i_required_time_to_departure;
};

public:
Expand All @@ -71,6 +84,8 @@ class TrafficLightModule : public SceneModuleInterfaceWithRTC
lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger,
const rclcpp::Clock::SharedPtr clock,
const std::shared_ptr<universe_utils::TimeKeeper> time_keeper,
const std::function<std::optional<TrafficSignalTimeToRedStamped>(void)> &
get_rest_time_to_red_signal,
const std::shared_ptr<planning_factor_interface::PlanningFactorInterface>
planning_factor_interface);

Expand Down Expand Up @@ -103,6 +118,15 @@ class TrafficLightModule : public SceneModuleInterfaceWithRTC

void updateTrafficSignal();

/**
* @brief Handle V2I Rest Time to Red Signal
* @param signed_arc_length_to_stop_point signed arc length to stop point
* @param output_path output path
* @return true if V2I is handled
*/
bool handleV2I(
const double & signed_arc_length_to_stop_point, const std::function<void()> & insert_stop_pose);

// Lane id
const int64_t lane_id_;

Expand Down Expand Up @@ -131,6 +155,9 @@ class TrafficLightModule : public SceneModuleInterfaceWithRTC

// Traffic Light State
TrafficSignal looking_tl_state_;

// V2I
std::function<std::optional<TrafficSignalTimeToRedStamped>(void)> get_rest_time_to_red_signal_;
};
} // namespace autoware::behavior_velocity_planner

Expand Down
Loading