Skip to content

Commit

Permalink
feat(autoware_behavior_velocity_traffic_light_module): add v2i to beh…
Browse files Browse the repository at this point in the history
…avior_velocity_traffic_light

Signed-off-by: Y.Hisaki <[email protected]>
  • Loading branch information
yhisaki committed Jan 23, 2025
1 parent cde1c78 commit 317bf1b
Show file tree
Hide file tree
Showing 6 changed files with 114 additions and 1 deletion.
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 @@ -57,6 +74,8 @@ void TrafficLightModuleManager::modifyPathVelocity(tier4_planning_msgs::msg::Pat
velocity_factor_array.header.frame_id = "map";
velocity_factor_array.header.stamp = clock_->now();

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 @@ -115,6 +134,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 @@ -175,6 +197,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] =
car_light.min_rest_time_to_red;
traffic_light_ids.push_back(state.traffic_light_group_id);
}
}
}

std::optional<double> 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,15 @@ class TrafficLightModuleManager : public SceneModuleManagerInterfaceWithRTC
const lanelet::TrafficLightConstPtr element,
const lanelet::TrafficLightConstPtr registered_element) const;

void updateV2IRestTimeInfo();

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

// V2I
autoware::universe_utils::InterProcessPollingSubscriber<
jpn_signal_v2i_msgs::msg::TrafficLightInfo>::SharedPtr v2i_subscriber_;
std::map<lanelet::Id, double> 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,15 @@
#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/logging.hpp>

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

#include <tf2/utils.h>

#include <memory>
#include <optional>

#ifdef ROS_DISTRO_GALACTIC
#include <tf2_eigen/tf2_eigen.h>
Expand All @@ -45,14 +47,16 @@ 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<double>(void)> & get_rest_time_to_red_signal,
const std::shared_ptr<motion_utils::PlanningFactorInterface> planning_factor_interface)
: SceneModuleInterfaceWithRTC(lane_id, logger, clock, time_keeper, planning_factor_interface),
lane_id_(lane_id),
traffic_light_reg_elem_(traffic_light_reg_elem),
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)
{
velocity_factor_.init(PlanningBehavior::TRAFFIC_SIGNAL);
planner_param_ = planner_param;
Expand Down Expand Up @@ -107,6 +111,33 @@ 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) {
std::optional<double> rest_time_to_red_signal = get_rest_time_to_red_signal_();
if (rest_time_to_red_signal.has_value()) {
const double rest_time_allowed_to_go_ahead =
rest_time_to_red_signal.value() - planner_param_.v2i_last_time_allowed_to_pass;
const double ego_v = planner_data_->current_velocity->twist.linear.x;

// Determine whether to stop based on velocity and time constraints
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);

// RTC
setSafe(!should_stop);
if (isActivated()) {
return true;
}
*path = insertStopPose(input_path, stop_line.value().first, stop_line.value().second);
return true;
}
RCLCPP_WARN(
logger_, "Failed to get V2I rest time to red signal. traffic_light_lane_id: %ld", lane_id_);
}

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

Expand Down
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 Down Expand Up @@ -63,6 +64,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 +77,7 @@ 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<double>(void)> & get_rest_time_to_red_signal,
const std::shared_ptr<motion_utils::PlanningFactorInterface> planning_factor_interface);

bool modifyPathVelocity(PathWithLaneId * path) override;
Expand Down Expand Up @@ -130,6 +137,9 @@ class TrafficLightModule : public SceneModuleInterfaceWithRTC

// Traffic Light State
TrafficSignal looking_tl_state_;

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

Expand Down

0 comments on commit 317bf1b

Please sign in to comment.