diff --git a/common/tier4_traffic_light_rviz_plugin/README.md b/common/tier4_traffic_light_rviz_plugin/README.md
index 953412a917432..91fb5bc124cb7 100644
--- a/common/tier4_traffic_light_rviz_plugin/README.md
+++ b/common/tier4_traffic_light_rviz_plugin/README.md
@@ -8,9 +8,9 @@ This plugin panel publishes dummy traffic light signals.
### Output
-| Name | Type | Description |
-| ------------------------------------------------------- | -------------------------------------------------------- | ----------------------------- |
-| `/perception/traffic_light_recognition/traffic_signals` | `autoware_auto_perception_msgs::msg::TrafficSignalArray` | Publish traffic light signals |
+| Name | Type | Description |
+| ------------------------------------------------------- | --------------------------------------------------- | ----------------------------- |
+| `/perception/traffic_light_recognition/traffic_signals` | `autoware_perception_msgs::msg::TrafficSignalArray` | Publish traffic light signals |
## HowToUse
diff --git a/common/tier4_traffic_light_rviz_plugin/package.xml b/common/tier4_traffic_light_rviz_plugin/package.xml
index 21d8bae8f6cff..2b118b429f1af 100644
--- a/common/tier4_traffic_light_rviz_plugin/package.xml
+++ b/common/tier4_traffic_light_rviz_plugin/package.xml
@@ -11,7 +11,7 @@
autoware_cmake
autoware_auto_mapping_msgs
- autoware_auto_perception_msgs
+ autoware_perception_msgs
lanelet2_extension
libqt5-core
libqt5-gui
diff --git a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp b/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp
index e4fb0095b8d0a..35c5a88a2f8a6 100644
--- a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp
+++ b/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp
@@ -34,6 +34,7 @@
#include
#include
+#undef signals
namespace rviz_plugins
{
TrafficLightPublishPanel::TrafficLightPublishPanel(QWidget * parent) : rviz_common::Panel(parent)
@@ -138,55 +139,55 @@ void TrafficLightPublishPanel::onSetTrafficLightState()
const auto shape = light_shape_combo_->currentText();
const auto status = light_status_combo_->currentText();
- TrafficLight traffic_light;
+ TrafficSignalElement traffic_light;
traffic_light.confidence = traffic_light_confidence_input_->value();
if (color == "RED") {
- traffic_light.color = TrafficLight::RED;
+ traffic_light.color = TrafficSignalElement::RED;
} else if (color == "AMBER") {
- traffic_light.color = TrafficLight::AMBER;
+ traffic_light.color = TrafficSignalElement::AMBER;
} else if (color == "GREEN") {
- traffic_light.color = TrafficLight::GREEN;
+ traffic_light.color = TrafficSignalElement::GREEN;
} else if (color == "WHITE") {
- traffic_light.color = TrafficLight::WHITE;
+ traffic_light.color = TrafficSignalElement::WHITE;
} else if (color == "UNKNOWN") {
- traffic_light.color = TrafficLight::UNKNOWN;
+ traffic_light.color = TrafficSignalElement::UNKNOWN;
}
if (shape == "CIRCLE") {
- traffic_light.shape = TrafficLight::CIRCLE;
+ traffic_light.shape = TrafficSignalElement::CIRCLE;
} else if (shape == "LEFT_ARROW") {
- traffic_light.shape = TrafficLight::LEFT_ARROW;
+ traffic_light.shape = TrafficSignalElement::LEFT_ARROW;
} else if (shape == "RIGHT_ARROW") {
- traffic_light.shape = TrafficLight::RIGHT_ARROW;
+ traffic_light.shape = TrafficSignalElement::RIGHT_ARROW;
} else if (shape == "UP_ARROW") {
- traffic_light.shape = TrafficLight::UP_ARROW;
+ traffic_light.shape = TrafficSignalElement::UP_ARROW;
} else if (shape == "DOWN_ARROW") {
- traffic_light.shape = TrafficLight::DOWN_ARROW;
+ traffic_light.shape = TrafficSignalElement::DOWN_ARROW;
} else if (shape == "DOWN_LEFT_ARROW") {
- traffic_light.shape = TrafficLight::DOWN_LEFT_ARROW;
+ traffic_light.shape = TrafficSignalElement::DOWN_LEFT_ARROW;
} else if (shape == "DOWN_RIGHT_ARROW") {
- traffic_light.shape = TrafficLight::DOWN_RIGHT_ARROW;
+ traffic_light.shape = TrafficSignalElement::DOWN_RIGHT_ARROW;
} else if (shape == "UNKNOWN") {
- traffic_light.shape = TrafficLight::UNKNOWN;
+ traffic_light.shape = TrafficSignalElement::UNKNOWN;
}
if (status == "SOLID_OFF") {
- traffic_light.status = TrafficLight::SOLID_OFF;
+ traffic_light.status = TrafficSignalElement::SOLID_OFF;
} else if (status == "SOLID_ON") {
- traffic_light.status = TrafficLight::SOLID_ON;
+ traffic_light.status = TrafficSignalElement::SOLID_ON;
} else if (status == "FLASHING") {
- traffic_light.status = TrafficLight::FLASHING;
+ traffic_light.status = TrafficSignalElement::FLASHING;
} else if (status == "UNKNOWN") {
- traffic_light.status = TrafficLight::UNKNOWN;
+ traffic_light.status = TrafficSignalElement::UNKNOWN;
}
TrafficSignal traffic_signal;
- traffic_signal.lights.push_back(traffic_light);
- traffic_signal.map_primitive_id = traffic_light_id;
+ traffic_signal.elements.push_back(traffic_light);
+ traffic_signal.traffic_signal_id = traffic_light_id;
for (auto & signal : extra_traffic_signals_.signals) {
- if (signal.map_primitive_id == traffic_light_id) {
+ if (signal.traffic_signal_id == traffic_light_id) {
signal = traffic_signal;
return;
}
@@ -247,7 +248,7 @@ void TrafficLightPublishPanel::createWallTimer()
void TrafficLightPublishPanel::onTimer()
{
if (enable_publish_) {
- extra_traffic_signals_.header.stamp = rclcpp::Clock().now();
+ extra_traffic_signals_.stamp = rclcpp::Clock().now();
pub_traffic_signals_->publish(extra_traffic_signals_);
}
@@ -260,35 +261,35 @@ void TrafficLightPublishPanel::onTimer()
for (size_t i = 0; i < extra_traffic_signals_.signals.size(); ++i) {
const auto & signal = extra_traffic_signals_.signals.at(i);
- if (signal.lights.empty()) {
+ if (signal.elements.empty()) {
continue;
}
- auto id_label = new QLabel(QString::number(signal.map_primitive_id));
+ auto id_label = new QLabel(QString::number(signal.traffic_signal_id));
id_label->setAlignment(Qt::AlignCenter);
auto color_label = new QLabel();
color_label->setAlignment(Qt::AlignCenter);
- const auto & light = signal.lights.front();
+ const auto & light = signal.elements.front();
switch (light.color) {
- case TrafficLight::RED:
+ case TrafficSignalElement::RED:
color_label->setText("RED");
color_label->setStyleSheet("background-color: #FF0000;");
break;
- case TrafficLight::AMBER:
+ case TrafficSignalElement::AMBER:
color_label->setText("AMBER");
color_label->setStyleSheet("background-color: #FFBF00;");
break;
- case TrafficLight::GREEN:
+ case TrafficSignalElement::GREEN:
color_label->setText("GREEN");
color_label->setStyleSheet("background-color: #7CFC00;");
break;
- case TrafficLight::WHITE:
+ case TrafficSignalElement::WHITE:
color_label->setText("WHITE");
color_label->setStyleSheet("background-color: #FFFFFF;");
break;
- case TrafficLight::UNKNOWN:
+ case TrafficSignalElement::UNKNOWN:
color_label->setText("UNKNOWN");
color_label->setStyleSheet("background-color: #808080;");
break;
@@ -300,31 +301,28 @@ void TrafficLightPublishPanel::onTimer()
shape_label->setAlignment(Qt::AlignCenter);
switch (light.shape) {
- case TrafficLight::CIRCLE:
+ case TrafficSignalElement::CIRCLE:
shape_label->setText("CIRCLE");
break;
- case TrafficLight::LEFT_ARROW:
+ case TrafficSignalElement::LEFT_ARROW:
shape_label->setText("LEFT_ARROW");
break;
- case TrafficLight::RIGHT_ARROW:
+ case TrafficSignalElement::RIGHT_ARROW:
shape_label->setText("RIGHT_ARROW");
break;
- case TrafficLight::UP_ARROW:
+ case TrafficSignalElement::UP_ARROW:
shape_label->setText("UP_ARROW");
break;
- case TrafficLight::DOWN_ARROW:
+ case TrafficSignalElement::DOWN_ARROW:
shape_label->setText("DOWN_ARROW");
break;
- case TrafficLight::DOWN_LEFT_ARROW:
+ case TrafficSignalElement::DOWN_LEFT_ARROW:
shape_label->setText("DOWN_LEFT_ARROW");
break;
- case TrafficLight::DOWN_RIGHT_ARROW:
+ case TrafficSignalElement::DOWN_RIGHT_ARROW:
shape_label->setText("DOWN_RIGHT_ARROW");
break;
- case TrafficLight::FLASHING:
- shape_label->setText("FLASHING");
- break;
- case TrafficLight::UNKNOWN:
+ case TrafficSignalElement::UNKNOWN:
shape_label->setText("UNKNOWN");
break;
default:
@@ -335,16 +333,16 @@ void TrafficLightPublishPanel::onTimer()
status_label->setAlignment(Qt::AlignCenter);
switch (light.status) {
- case TrafficLight::SOLID_OFF:
+ case TrafficSignalElement::SOLID_OFF:
status_label->setText("SOLID_OFF");
break;
- case TrafficLight::SOLID_ON:
+ case TrafficSignalElement::SOLID_ON:
status_label->setText("SOLID_ON");
break;
- case TrafficLight::FLASHING:
+ case TrafficSignalElement::FLASHING:
status_label->setText("FLASHING");
break;
- case TrafficLight::UNKNOWN:
+ case TrafficSignalElement::UNKNOWN:
status_label->setText("UNKNOWN");
break;
default:
@@ -375,11 +373,9 @@ void TrafficLightPublishPanel::onVectorMap(const HADMapBin::ConstSharedPtr msg)
std::string info = "Fetching traffic lights :";
std::string delim = " ";
for (auto && tl_reg_elem_ptr : tl_reg_elems) {
- for (auto && traffic_light : tl_reg_elem_ptr->trafficLights()) {
- auto id = static_cast(traffic_light.id());
- info += (std::exchange(delim, ", ") + std::to_string(id));
- traffic_light_ids_.insert(id);
- }
+ auto id = static_cast(tl_reg_elem_ptr->id());
+ info += (std::exchange(delim, ", ") + std::to_string(id));
+ traffic_light_ids_.insert(id);
}
RCLCPP_INFO_STREAM(raw_node_->get_logger(), info);
received_vector_map_ = true;
diff --git a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.hpp b/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.hpp
index 75e6405417084..e54b6a301873b 100644
--- a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.hpp
+++ b/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.hpp
@@ -27,7 +27,7 @@
#include
#include
-#include
+#include
#endif
#include
@@ -36,10 +36,9 @@ namespace rviz_plugins
{
using autoware_auto_mapping_msgs::msg::HADMapBin;
-using autoware_auto_perception_msgs::msg::TrafficLight;
-using autoware_auto_perception_msgs::msg::TrafficSignal;
-using autoware_auto_perception_msgs::msg::TrafficSignalArray;
-
+using autoware_perception_msgs::msg::TrafficSignal;
+using autoware_perception_msgs::msg::TrafficSignalArray;
+using autoware_perception_msgs::msg::TrafficSignalElement;
class TrafficLightPublishPanel : public rviz_common::Panel
{
Q_OBJECT
diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py
index 59e8038e49188..62d4c5b7188ee 100644
--- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py
+++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.py
@@ -177,10 +177,6 @@ def launch_setup(context, *args, **kwargs):
"~/input/traffic_signals",
"/perception/traffic_light_recognition/traffic_signals",
),
- (
- "~/input/external_traffic_signals",
- "/external/traffic_light_recognition/traffic_signals",
- ),
(
"~/input/external_velocity_limit_mps",
"/planning/scenario_planning/max_velocity_default",
diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp
index 29a4a8efa719f..0adda77a2ad72 100644
--- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp
+++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp
@@ -46,7 +46,9 @@ using visualization_msgs::msg::MarkerArray;
// TODO(sugahara) move to util
PathWithLaneId combineReferencePath(const PathWithLaneId & path1, const PathWithLaneId & path2);
-lanelet::ConstLanelets getPullOverLanes(const RouteHandler & route_handler, const bool left_side);
+lanelet::ConstLanelets getPullOverLanes(
+ const RouteHandler & route_handler, const bool left_side, const double backward_distance,
+ const double forward_distance);
PredictedObjects filterObjectsByLateralDistance(
const Pose & ego_pose, const double vehicle_width, const PredictedObjects & objects,
const double distance_thresh, const bool filter_inside);
diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp
index 78c063421f29a..c2b372d2403e5 100644
--- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp
+++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp
@@ -881,17 +881,35 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects(
}
// output avoidance path under lateral jerk constraints.
- const auto feasible_shift_length = PathShifter::calcLateralDistFromJerk(
+ const auto feasible_relative_shift_length = PathShifter::calcLateralDistFromJerk(
remaining_distance, helper_.getLateralMaxJerkLimit(), helper_.getAvoidanceEgoSpeed());
- RCLCPP_WARN_THROTTLE(
- getLogger(), *clock_, 1000,
- "original shift length is not feasible. generate avoidance path under the constraints. "
- "[original: (%.2f) actual: (%.2f)]",
- std::abs(avoiding_shift), feasible_shift_length);
+ if (std::abs(feasible_relative_shift_length) < parameters_->lateral_execution_threshold) {
+ object.reason = "LessThanExecutionThreshold";
+ return boost::none;
+ }
+
+ const auto feasible_shift_length =
+ desire_shift_length > 0.0 ? feasible_relative_shift_length + current_ego_shift
+ : -1.0 * feasible_relative_shift_length + current_ego_shift;
+
+ const auto feasible =
+ std::abs(feasible_shift_length - object.overhang_dist) <
+ 0.5 * planner_data_->parameters.vehicle_width + object_parameter.safety_buffer_lateral;
+ if (feasible) {
+ RCLCPP_WARN_THROTTLE(
+ getLogger(), *clock_, 1000, "feasible shift length is not enough to avoid. ");
+ object.reason = AvoidanceDebugFactor::INSUFFICIENT_LATERAL_MARGIN;
+ return boost::none;
+ }
+
+ {
+ RCLCPP_WARN_THROTTLE(
+ getLogger(), *clock_, 1000, "use feasible shift length. [original: (%.2f) actual: (%.2f)]",
+ std::abs(avoiding_shift), feasible_relative_shift_length);
+ }
- return desire_shift_length > 0.0 ? feasible_shift_length + current_ego_shift
- : -1.0 * feasible_shift_length + current_ego_shift;
+ return feasible_shift_length;
};
const auto is_forward_object = [](const auto & object) { return object.longitudinal > 0.0; };
diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp
index 6f22ee9b1412b..37d44154789a6 100644
--- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp
+++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp
@@ -335,8 +335,9 @@ bool GoalPlannerModule::isExecutionRequested() const
// if (A) or (B) is met execute pull over
// (A) target lane is `road` and same to the current lanes
// (B) target lane is `road_shoulder` and neighboring to the current lanes
- const lanelet::ConstLanelets pull_over_lanes =
- goal_planner_utils::getPullOverLanes(*(route_handler), left_side_parking_);
+ const lanelet::ConstLanelets pull_over_lanes = goal_planner_utils::getPullOverLanes(
+ *(route_handler), left_side_parking_, parameters_->backward_goal_search_length,
+ parameters_->forward_goal_search_length);
lanelet::ConstLanelet target_lane{};
lanelet::utils::query::getClosestLanelet(pull_over_lanes, goal_pose, &target_lane);
if (!isCrossingPossible(current_lane, target_lane)) {
@@ -387,8 +388,9 @@ Pose GoalPlannerModule::calcRefinedGoal(const Pose & goal_pose) const
const double base_link2front = planner_data_->parameters.base_link2front;
const double base_link2rear = planner_data_->parameters.base_link2rear;
- const lanelet::ConstLanelets pull_over_lanes =
- goal_planner_utils::getPullOverLanes(*(planner_data_->route_handler), left_side_parking_);
+ const lanelet::ConstLanelets pull_over_lanes = goal_planner_utils::getPullOverLanes(
+ *(planner_data_->route_handler), left_side_parking_, parameters_->backward_goal_search_length,
+ parameters_->forward_goal_search_length);
lanelet::Lanelet closest_pull_over_lanelet{};
lanelet::utils::query::getClosestLanelet(pull_over_lanes, goal_pose, &closest_pull_over_lanelet);
@@ -643,8 +645,9 @@ void GoalPlannerModule::setLanes()
planner_data_, parameters_->backward_goal_search_length,
parameters_->forward_goal_search_length,
/*forward_only_in_route*/ false);
- status_.pull_over_lanes =
- goal_planner_utils::getPullOverLanes(*(planner_data_->route_handler), left_side_parking_);
+ status_.pull_over_lanes = goal_planner_utils::getPullOverLanes(
+ *(planner_data_->route_handler), left_side_parking_, parameters_->backward_goal_search_length,
+ parameters_->forward_goal_search_length);
status_.lanes =
utils::generateDrivableLanesWithShoulderLanes(status_.current_lanes, status_.pull_over_lanes);
}
@@ -1487,8 +1490,9 @@ bool GoalPlannerModule::isSafePath() const
const auto current_lanes = utils::getExtendedCurrentLanes(
planner_data_, backward_path_length, std::numeric_limits::max(),
/*forward_only_in_route*/ true);
- const auto pull_over_lanes =
- goal_planner_utils::getPullOverLanes(*(route_handler), left_side_parking_);
+ const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
+ *route_handler, left_side_parking_, parameters_->backward_goal_search_length,
+ parameters_->forward_goal_search_length);
const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(pull_over_path.points);
const auto & common_param = planner_data_->parameters;
const std::pair terminal_velocity_and_accel =
@@ -1655,8 +1659,9 @@ bool GoalPlannerModule::checkOriginalGoalIsInShoulder() const
const auto & route_handler = planner_data_->route_handler;
const Pose & goal_pose = route_handler->getOriginalGoalPose();
- const lanelet::ConstLanelets pull_over_lanes =
- goal_planner_utils::getPullOverLanes(*(route_handler), left_side_parking_);
+ const lanelet::ConstLanelets pull_over_lanes = goal_planner_utils::getPullOverLanes(
+ *(route_handler), left_side_parking_, parameters_->backward_goal_search_length,
+ parameters_->forward_goal_search_length);
lanelet::ConstLanelet target_lane{};
lanelet::utils::query::getClosestLanelet(pull_over_lanes, goal_pose, &target_lane);
diff --git a/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp b/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp
index 9656094f5a478..9322350877ad1 100644
--- a/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp
+++ b/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp
@@ -63,8 +63,9 @@ boost::optional FreespacePullOver::plan(const Pose & goal_pose)
const auto road_lanes = utils::getExtendedCurrentLanes(
planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length,
/*forward_only_in_route*/ false);
- const auto pull_over_lanes =
- goal_planner_utils::getPullOverLanes(*(planner_data_->route_handler), left_side_parking_);
+ const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
+ *(planner_data_->route_handler), left_side_parking_, parameters_.backward_goal_search_length,
+ parameters_.forward_goal_search_length);
if (road_lanes.empty() || pull_over_lanes.empty()) {
return {};
}
diff --git a/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp b/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp
index 5594f7af1c428..ed0106d891bb4 100644
--- a/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp
+++ b/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp
@@ -47,8 +47,9 @@ boost::optional GeometricPullOver::plan(const Pose & goal_pose)
const auto road_lanes = utils::getExtendedCurrentLanes(
planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length,
/*forward_only_in_route*/ false);
- const auto pull_over_lanes =
- goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_);
+ const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
+ *route_handler, left_side_parking_, parameters_.backward_goal_search_length,
+ parameters_.forward_goal_search_length);
if (road_lanes.empty() || pull_over_lanes.empty()) {
return {};
}
diff --git a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp
index e12ee576a5d4b..19dec4d3c97d1 100644
--- a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp
+++ b/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp
@@ -57,8 +57,9 @@ GoalCandidates GoalSearcher::search(const Pose & original_goal_pose)
const double base_link2front = planner_data_->parameters.base_link2front;
const double base_link2rear = planner_data_->parameters.base_link2rear;
- const auto pull_over_lanes =
- goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_);
+ const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
+ *route_handler, left_side_parking_, parameters_.backward_goal_search_length,
+ parameters_.forward_goal_search_length);
auto lanes = utils::getExtendedCurrentLanes(
planner_data_, backward_length, forward_length,
/*forward_only_in_route*/ false);
@@ -157,8 +158,9 @@ void GoalSearcher::update(GoalCandidates & goal_candidates) const
}
// check margin with pull over lane objects
- const auto pull_over_lanes =
- goal_planner_utils::getPullOverLanes(*(planner_data_->route_handler), left_side_parking_);
+ const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
+ *(planner_data_->route_handler), left_side_parking_, parameters_.backward_goal_search_length,
+ parameters_.forward_goal_search_length);
const auto [shoulder_lane_objects, others] =
utils::path_safety_checker::separateObjectsByLanelets(
*(planner_data_->dynamic_object), pull_over_lanes);
diff --git a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp b/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp
index c5ac14d4d9727..aeb28d74e5f95 100644
--- a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp
+++ b/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp
@@ -49,16 +49,16 @@ boost::optional ShiftPullOver::plan(const Pose & goal_pose)
const auto road_lanes = utils::getExtendedCurrentLanes(
planner_data_, backward_search_length, forward_search_length,
/*forward_only_in_route*/ false);
- const auto shoulder_lanes =
- goal_planner_utils::getPullOverLanes(*route_handler, left_side_parking_);
- if (road_lanes.empty() || shoulder_lanes.empty()) {
+ const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
+ *route_handler, left_side_parking_, backward_search_length, forward_search_length);
+ if (road_lanes.empty() || pull_over_lanes.empty()) {
return {};
}
// find safe one from paths with different jerk
for (double lateral_jerk = min_jerk; lateral_jerk <= max_jerk; lateral_jerk += jerk_resolution) {
const auto pull_over_path =
- generatePullOverPath(road_lanes, shoulder_lanes, goal_pose, lateral_jerk);
+ generatePullOverPath(road_lanes, pull_over_lanes, goal_pose, lateral_jerk);
if (!pull_over_path) continue;
return *pull_over_path;
}
diff --git a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp b/planning/behavior_path_planner/src/utils/goal_planner/util.cpp
index 0d58a54431be0..aa3380c2b99df 100644
--- a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp
+++ b/planning/behavior_path_planner/src/utils/goal_planner/util.cpp
@@ -55,36 +55,37 @@ PathWithLaneId combineReferencePath(const PathWithLaneId & path1, const PathWith
return path;
}
-lanelet::ConstLanelets getPullOverLanes(const RouteHandler & route_handler, const bool left_side)
+lanelet::ConstLanelets getPullOverLanes(
+ const RouteHandler & route_handler, const bool left_side, const double backward_distance,
+ const double forward_distance)
{
const Pose goal_pose = route_handler.getOriginalGoalPose();
+ // Buffer to get enough lanes in front of the goal, need much longer than the pull over distance.
+ // In the case of loop lanes, it may not be possible to extend the lane forward.
+ // todo(kosuek55): automatically calculates this distance.
+ const double backward_distance_with_buffer = backward_distance + 100;
+
lanelet::ConstLanelet target_shoulder_lane{};
if (route_handler::RouteHandler::getPullOverTarget(
route_handler.getShoulderLanelets(), goal_pose, &target_shoulder_lane)) {
// pull over on shoulder lane
- return route_handler.getShoulderLaneletSequence(target_shoulder_lane, goal_pose);
+ return route_handler.getShoulderLaneletSequence(
+ target_shoulder_lane, goal_pose, backward_distance_with_buffer, forward_distance);
}
- // pull over on road lane
lanelet::ConstLanelet closest_lane{};
route_handler.getClosestLaneletWithinRoute(goal_pose, &closest_lane);
-
lanelet::ConstLanelet outermost_lane{};
if (left_side) {
- outermost_lane = route_handler.getMostLeftLanelet(closest_lane);
+ outermost_lane = route_handler.getMostLeftLanelet(closest_lane, false, true);
} else {
- outermost_lane = route_handler.getMostRightLanelet(closest_lane);
- }
-
- lanelet::ConstLanelet outermost_shoulder_lane;
- if (route_handler.getLeftShoulderLanelet(outermost_lane, &outermost_shoulder_lane)) {
- return route_handler.getShoulderLaneletSequence(outermost_shoulder_lane, goal_pose);
+ outermost_lane = route_handler.getMostRightLanelet(closest_lane, false, true);
}
- const bool dist = std::numeric_limits::max();
constexpr bool only_route_lanes = false;
- return route_handler.getLaneletSequence(outermost_lane, dist, dist, only_route_lanes);
+ return route_handler.getLaneletSequence(
+ outermost_lane, backward_distance_with_buffer, forward_distance, only_route_lanes);
}
PredictedObjects filterObjectsByLateralDistance(
diff --git a/planning/behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_crosswalk_module/package.xml
index 75f96c9194aef..66f326ed799af 100644
--- a/planning/behavior_velocity_crosswalk_module/package.xml
+++ b/planning/behavior_velocity_crosswalk_module/package.xml
@@ -21,6 +21,7 @@
autoware_auto_perception_msgs
autoware_auto_planning_msgs
autoware_auto_tf2
+ autoware_perception_msgs
behavior_velocity_planner_common
eigen
geometry_msgs
diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp
index 6d2a3110cbdb7..7a972891fd053 100644
--- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp
+++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp
@@ -938,28 +938,25 @@ bool CrosswalkModule::isRedSignalForPedestrians() const
crosswalk_.regulatoryElementsAs();
for (const auto & traffic_lights_reg_elem : traffic_lights_reg_elems) {
- lanelet::ConstLineStringsOrPolygons3d traffic_lights = traffic_lights_reg_elem->trafficLights();
- for (const auto & traffic_light : traffic_lights) {
- const auto ll_traffic_light = static_cast(traffic_light);
- const auto traffic_signal_stamped = planner_data_->getTrafficSignal(ll_traffic_light.id());
- if (!traffic_signal_stamped) {
- continue;
- }
+ const auto traffic_signal_stamped =
+ planner_data_->getTrafficSignal(traffic_lights_reg_elem->id());
+ if (!traffic_signal_stamped) {
+ continue;
+ }
- if (
- planner_param_.traffic_light_state_timeout <
- (clock_->now() - traffic_signal_stamped->header.stamp).seconds()) {
- continue;
- }
+ if (
+ planner_param_.traffic_light_state_timeout <
+ (clock_->now() - traffic_signal_stamped->stamp).seconds()) {
+ continue;
+ }
- const auto & lights = traffic_signal_stamped->signal.lights;
- if (lights.empty()) {
- continue;
- }
+ const auto & lights = traffic_signal_stamped->signal.elements;
+ if (lights.empty()) {
+ continue;
+ }
- if (lights.front().color == TrafficLight::RED) {
- return true;
- }
+ if (lights.front().color == TrafficSignalElement::RED) {
+ return true;
}
}
diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp
index e0851366d7f71..65f3772cd4d33 100644
--- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp
+++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp
@@ -50,8 +50,8 @@ namespace behavior_velocity_planner
using autoware_auto_perception_msgs::msg::ObjectClassification;
using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;
-using autoware_auto_perception_msgs::msg::TrafficLight;
using autoware_auto_planning_msgs::msg::PathWithLaneId;
+using autoware_perception_msgs::msg::TrafficSignalElement;
using lanelet::autoware::Crosswalk;
using tier4_api_msgs::msg::CrosswalkStatus;
using tier4_autoware_utils::Polygon2d;
diff --git a/planning/behavior_velocity_intersection_module/package.xml b/planning/behavior_velocity_intersection_module/package.xml
index f22e9d788fc65..879b26209a05e 100644
--- a/planning/behavior_velocity_intersection_module/package.xml
+++ b/planning/behavior_velocity_intersection_module/package.xml
@@ -19,6 +19,7 @@
autoware_auto_perception_msgs
autoware_auto_planning_msgs
+ autoware_perception_msgs
behavior_velocity_planner_common
geometry_msgs
interpolation
diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp
index 0dfadf2f00d7a..0c6726b45dcbc 100644
--- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp
+++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp
@@ -335,9 +335,16 @@ void reactRTCApprovalByDecisionResult(
rclcpp::get_logger("reactRTCApprovalByDecisionResult"),
"StuckStop, approval = (default: %d, occlusion: %d)", rtc_default_approved,
rtc_occlusion_approved);
+ const auto closest_idx = decision_result.stop_lines.closest_idx;
if (!rtc_default_approved) {
// use default_rtc uuid for stuck vehicle detection
- const auto stop_line_idx = decision_result.stop_line_idx;
+ auto stop_line_idx = decision_result.stop_line_idx;
+ if (
+ !decision_result.is_detection_area_empty &&
+ motion_utils::calcSignedArcLength(path->points, stop_line_idx, closest_idx) >
+ planner_param.common.stop_overshoot_margin) {
+ stop_line_idx = decision_result.stop_lines.default_stop_line;
+ }
planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path);
debug_data->collision_stop_wall_pose =
planning_utils::getAheadPose(stop_line_idx, baselink2front, *path);
@@ -347,7 +354,7 @@ void reactRTCApprovalByDecisionResult(
stop_factor.stop_factor_points = planning_utils::toRosPoints(debug_data->conflicting_targets);
planning_utils::appendStopReason(stop_factor, stop_reason);
velocity_factor->set(
- path->points, path->points.at(decision_result.stop_lines.closest_idx).point.pose,
+ path->points, path->points.at(closest_idx).point.pose,
path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION);
}
}
@@ -363,7 +370,7 @@ void reactRTCApprovalByDecisionResult(
stop_factor.stop_pose = path->points.at(occlusion_stop_line_idx).point.pose;
planning_utils::appendStopReason(stop_factor, stop_reason);
velocity_factor->set(
- path->points, path->points.at(decision_result.stop_lines.closest_idx).point.pose,
+ path->points, path->points.at(closest_idx).point.pose,
path->points.at(occlusion_stop_line_idx).point.pose, VelocityFactor::INTERSECTION);
}
}
@@ -774,7 +781,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
const auto & conflicting_area = intersection_lanelets_.value().conflicting_area();
const auto path_lanelets_opt = util::generatePathLanelets(
lanelets_on_path, interpolated_path_info, associative_ids_, first_conflicting_area.value(),
- conflicting_area, closest_idx, planner_data_->vehicle_info_.vehicle_width_m);
+ conflicting_area, first_attention_area, intersection_lanelets_.value().attention_area(),
+ closest_idx, planner_data_->vehicle_info_.vehicle_width_m);
if (!path_lanelets_opt.has_value()) {
RCLCPP_DEBUG(logger_, "failed to generate PathLanelets");
return IntersectionModule::Indecisive{};
diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp
index cd6d941b43de2..d78b7252d0878 100644
--- a/planning/behavior_velocity_intersection_module/src/util.cpp
+++ b/planning/behavior_velocity_intersection_module/src/util.cpp
@@ -704,9 +704,10 @@ bool hasAssociatedTrafficLight(lanelet::ConstLanelet lane)
}
bool isTrafficLightArrowActivated(
- lanelet::ConstLanelet lane,
- const std::map & tl_infos)
+ lanelet::ConstLanelet lane, const std::map & tl_infos)
{
+ using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement;
+
const auto & turn_direction = lane.attributeOr("turn_direction", "else");
std::optional tl_id = std::nullopt;
for (auto && tl_reg_elem : lane.regulatoryElementsAs()) {
@@ -723,16 +724,13 @@ bool isTrafficLightArrowActivated(
return false;
}
const auto & tl_info = tl_info_it->second;
- for (auto && tl_light : tl_info.signal.lights) {
- if (tl_light.color != autoware_auto_perception_msgs::msg::TrafficLight::GREEN) continue;
- if (tl_light.status != autoware_auto_perception_msgs::msg::TrafficLight::SOLID_ON) continue;
- if (
- turn_direction == std::string("left") &&
- tl_light.shape == autoware_auto_perception_msgs::msg::TrafficLight::LEFT_ARROW)
+ for (auto && tl_light : tl_info.signal.elements) {
+ if (tl_light.color != TrafficSignalElement::GREEN) continue;
+ if (tl_light.status != TrafficSignalElement::SOLID_ON) continue;
+ if (turn_direction == std::string("left") && tl_light.shape == TrafficSignalElement::LEFT_ARROW)
return true;
if (
- turn_direction == std::string("right") &&
- tl_light.shape == autoware_auto_perception_msgs::msg::TrafficLight::RIGHT_ARROW)
+ turn_direction == std::string("right") && tl_light.shape == TrafficSignalElement::RIGHT_ARROW)
return true;
}
return false;
@@ -1155,7 +1153,9 @@ std::optional generatePathLanelets(
const lanelet::ConstLanelets & lanelets_on_path,
const util::InterpolatedPathInfo & interpolated_path_info, const std::set & associative_ids,
const lanelet::CompoundPolygon3d & first_conflicting_area,
- const std::vector & conflicting_areas, const size_t closest_idx,
+ const std::vector & conflicting_areas,
+ const std::optional & first_attention_area,
+ const std::vector & attention_areas, const size_t closest_idx,
const double width)
{
const auto & assigned_lane_interval_opt = interpolated_path_info.lane_id_interval;
@@ -1195,9 +1195,13 @@ std::optional generatePathLanelets(
}
const auto first_inside_conflicting_idx_opt =
- getFirstPointInsidePolygon(path, assigned_lane_interval, first_conflicting_area);
+ first_attention_area.has_value()
+ ? getFirstPointInsidePolygon(path, assigned_lane_interval, first_attention_area.value())
+ : getFirstPointInsidePolygon(path, assigned_lane_interval, first_conflicting_area);
const auto last_inside_conflicting_idx_opt =
- getFirstPointInsidePolygons(path, assigned_lane_interval, conflicting_areas, false);
+ first_attention_area.has_value()
+ ? getFirstPointInsidePolygons(path, assigned_lane_interval, attention_areas, false)
+ : getFirstPointInsidePolygons(path, assigned_lane_interval, conflicting_areas, false);
if (first_inside_conflicting_idx_opt && last_inside_conflicting_idx_opt) {
const auto first_inside_conflicting_idx = first_inside_conflicting_idx_opt.value();
const auto last_inside_conflicting_idx = last_inside_conflicting_idx_opt.value().first;
diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp
index 1361847b4b980..e766da6651417 100644
--- a/planning/behavior_velocity_intersection_module/src/util.hpp
+++ b/planning/behavior_velocity_intersection_module/src/util.hpp
@@ -112,8 +112,7 @@ std::optional getIntersectionArea(
bool hasAssociatedTrafficLight(lanelet::ConstLanelet lane);
bool isTrafficLightArrowActivated(
- lanelet::ConstLanelet lane,
- const std::map & tl_infos);
+ lanelet::ConstLanelet lane, const std::map & tl_infos);
std::vector generateDetectionLaneDivisions(
lanelet::ConstLanelets detection_lanelets,
@@ -158,7 +157,9 @@ std::optional generatePathLanelets(
const lanelet::ConstLanelets & lanelets_on_path,
const util::InterpolatedPathInfo & interpolated_path_info, const std::set & associative_ids,
const lanelet::CompoundPolygon3d & first_conflicting_area,
- const std::vector & conflicting_areas, const size_t closest_idx,
+ const std::vector & conflicting_areas,
+ const std::optional & first_attention_area,
+ const std::vector & attention_areas, const size_t closest_idx,
const double width);
} // namespace util
diff --git a/planning/behavior_velocity_planner/README.md b/planning/behavior_velocity_planner/README.md
index 25546c95074c3..519e68764b450 100644
--- a/planning/behavior_velocity_planner/README.md
+++ b/planning/behavior_velocity_planner/README.md
@@ -29,15 +29,15 @@ So for example, in order to stop at a stop line with the vehicles' front on the
## Input topics
-| Name | Type | Description |
-| ----------------------------------------- | ------------------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------- |
-| `~input/path_with_lane_id` | autoware_auto_planning_msgs::msg::PathWithLaneId | path with lane_id |
-| `~input/vector_map` | autoware_auto_mapping_msgs::msg::HADMapBin | vector map |
-| `~input/vehicle_odometry` | nav_msgs::msg::Odometry | vehicle velocity |
-| `~input/dynamic_objects` | autoware_auto_perception_msgs::msg::PredictedObjects | dynamic objects |
-| `~input/no_ground_pointcloud` | sensor_msgs::msg::PointCloud2 | obstacle pointcloud |
-| `~/input/compare_map_filtered_pointcloud` | sensor_msgs::msg::PointCloud2 | obstacle pointcloud filtered by compare map. Note that this is used only when the detection method of run out module is Points. |
-| `~input/traffic_signals` | autoware_auto_perception_msgs::msg::TrafficSignalArray | traffic light states |
+| Name | Type | Description |
+| ----------------------------------------- | ---------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------- |
+| `~input/path_with_lane_id` | autoware_auto_planning_msgs::msg::PathWithLaneId | path with lane_id |
+| `~input/vector_map` | autoware_auto_mapping_msgs::msg::HADMapBin | vector map |
+| `~input/vehicle_odometry` | nav_msgs::msg::Odometry | vehicle velocity |
+| `~input/dynamic_objects` | autoware_auto_perception_msgs::msg::PredictedObjects | dynamic objects |
+| `~input/no_ground_pointcloud` | sensor_msgs::msg::PointCloud2 | obstacle pointcloud |
+| `~/input/compare_map_filtered_pointcloud` | sensor_msgs::msg::PointCloud2 | obstacle pointcloud filtered by compare map. Note that this is used only when the detection method of run out module is Points. |
+| `~input/traffic_signals` | autoware_perception_msgs::msg::TrafficSignalArray | traffic light states |
## Output topics
diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp
index 12503f743b0f2..0aed3015fbf40 100644
--- a/planning/behavior_velocity_planner/src/node.cpp
+++ b/planning/behavior_velocity_planner/src/node.cpp
@@ -99,7 +99,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
std::bind(&BehaviorVelocityPlannerNode::onLaneletMap, this, _1),
createSubscriptionOptions(this));
sub_traffic_signals_ =
- this->create_subscription(
+ this->create_subscription(
"~/input/traffic_signals", 1,
std::bind(&BehaviorVelocityPlannerNode::onTrafficSignals, this, _1),
createSubscriptionOptions(this));
@@ -287,15 +287,15 @@ void BehaviorVelocityPlannerNode::onLaneletMap(
}
void BehaviorVelocityPlannerNode::onTrafficSignals(
- const autoware_auto_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg)
+ const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg)
{
std::lock_guard lock(mutex_);
for (const auto & signal : msg->signals) {
- autoware_auto_perception_msgs::msg::TrafficSignalStamped traffic_signal;
- traffic_signal.header = msg->header;
+ TrafficSignalStamped traffic_signal;
+ traffic_signal.stamp = msg->stamp;
traffic_signal.signal = signal;
- planner_data_.traffic_light_id_map[signal.map_primitive_id] = traffic_signal;
+ planner_data_.traffic_light_id_map[signal.traffic_signal_id] = traffic_signal;
}
}
diff --git a/planning/behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/src/node.hpp
index 91172fdd77da8..98cdaeb3e0cdb 100644
--- a/planning/behavior_velocity_planner/src/node.hpp
+++ b/planning/behavior_velocity_planner/src/node.hpp
@@ -61,7 +61,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
rclcpp::Subscription::SharedPtr sub_vehicle_odometry_;
rclcpp::Subscription::SharedPtr sub_acceleration_;
rclcpp::Subscription::SharedPtr sub_lanelet_map_;
- rclcpp::Subscription::SharedPtr
+ rclcpp::Subscription::SharedPtr
sub_traffic_signals_;
rclcpp::Subscription::SharedPtr
sub_virtual_traffic_light_states_;
@@ -77,7 +77,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
void onAcceleration(const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg);
void onLaneletMap(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg);
void onTrafficSignals(
- const autoware_auto_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg);
+ const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg);
void onVirtualTrafficLightStates(
const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg);
void onOccupancyGrid(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg);
diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp
index 44d3184a5f6b7..2668d83b0f510 100644
--- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp
+++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp
@@ -17,14 +17,14 @@
#include "route_handler/route_handler.hpp"
+#include
#include
#include
#include
#include
#include
-#include
-#include
+#include
#include
#include
#include
@@ -83,7 +83,7 @@ struct PlannerData
double ego_nearest_yaw_threshold;
// other internal data
- std::map traffic_light_id_map;
+ std::map traffic_light_id_map;
boost::optional external_velocity_limit;
tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr virtual_traffic_light_states;
@@ -132,14 +132,12 @@ struct PlannerData
return true;
}
- std::shared_ptr getTrafficSignal(
- const int id) const
+ std::shared_ptr getTrafficSignal(const int id) const
{
if (traffic_light_id_map.count(id) == 0) {
return {};
}
- return std::make_shared(
- traffic_light_id_map.at(id));
+ return std::make_shared(traffic_light_id_map.at(id));
}
};
} // namespace behavior_velocity_planner
diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp
index 14b009ceb0748..14c80b59acf5e 100644
--- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp
+++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp
@@ -27,6 +27,7 @@
#include
#include
#include
+#include
#include
#include
#include
@@ -78,6 +79,12 @@ struct PointWithSearchRangeIndex
SearchRangeIndex index;
};
+struct TrafficSignalStamped
+{
+ builtin_interfaces::msg::Time stamp;
+ autoware_perception_msgs::msg::TrafficSignal signal;
+};
+
using geometry_msgs::msg::Pose;
using BasicPolygons2d = std::vector;
using Polygons2d = std::vector;
diff --git a/planning/behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner_common/package.xml
index 6a7a6f698bfbc..aedbab65068fb 100644
--- a/planning/behavior_velocity_planner_common/package.xml
+++ b/planning/behavior_velocity_planner_common/package.xml
@@ -19,9 +19,9 @@
autoware_adapi_v1_msgs
autoware_auto_mapping_msgs
- autoware_auto_perception_msgs
autoware_auto_planning_msgs
autoware_auto_tf2
+ autoware_perception_msgs
diagnostic_msgs
eigen
geometry_msgs
diff --git a/planning/behavior_velocity_traffic_light_module/package.xml b/planning/behavior_velocity_traffic_light_module/package.xml
index a8733c5dcf5be..c658f0890b986 100644
--- a/planning/behavior_velocity_traffic_light_module/package.xml
+++ b/planning/behavior_velocity_traffic_light_module/package.xml
@@ -18,8 +18,8 @@
eigen3_cmake_module
autoware_adapi_v1_msgs
- autoware_auto_perception_msgs
autoware_auto_planning_msgs
+ autoware_perception_msgs
behavior_velocity_planner_common
eigen
geometry_msgs
diff --git a/planning/behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_traffic_light_module/src/manager.cpp
index 1b0646f4bee00..f035544b81592 100644
--- a/planning/behavior_velocity_traffic_light_module/src/manager.cpp
+++ b/planning/behavior_velocity_traffic_light_module/src/manager.cpp
@@ -41,7 +41,7 @@ TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node)
planner_param_.enable_pass_judge = getOrDeclareParameter(node, ns + ".enable_pass_judge");
planner_param_.yellow_lamp_period =
getOrDeclareParameter(node, ns + ".yellow_lamp_period");
- pub_tl_state_ = node.create_publisher(
+ pub_tl_state_ = node.create_publisher(
"~/output/traffic_signal", 1);
}
@@ -51,9 +51,7 @@ void TrafficLightModuleManager::modifyPathVelocity(
visualization_msgs::msg::MarkerArray debug_marker_array;
visualization_msgs::msg::MarkerArray virtual_wall_marker_array;
- autoware_auto_perception_msgs::msg::LookingTrafficSignal tl_state;
- tl_state.header.stamp = path->header.stamp;
- tl_state.is_module_running = false;
+ autoware_perception_msgs::msg::TrafficSignal tl_state;
autoware_adapi_v1_msgs::msg::VelocityFactorArray velocity_factor_array;
velocity_factor_array.header.frame_id = "map";
diff --git a/planning/behavior_velocity_traffic_light_module/src/manager.hpp b/planning/behavior_velocity_traffic_light_module/src/manager.hpp
index 450cba09e1e08..c36c6af1128ce 100644
--- a/planning/behavior_velocity_traffic_light_module/src/manager.hpp
+++ b/planning/behavior_velocity_traffic_light_module/src/manager.hpp
@@ -55,8 +55,7 @@ class TrafficLightModuleManager : public SceneModuleManagerInterfaceWithRTC
const lanelet::TrafficLightConstPtr registered_element) const;
// Debug
- rclcpp::Publisher::SharedPtr
- pub_tl_state_;
+ rclcpp::Publisher::SharedPtr pub_tl_state_;
boost::optional first_ref_stop_path_point_index_;
};
diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_traffic_light_module/src/scene.cpp
index 679a2f0cb9320..e0633926e35df 100644
--- a/planning/behavior_velocity_traffic_light_module/src/scene.cpp
+++ b/planning/behavior_velocity_traffic_light_module/src/scene.cpp
@@ -159,32 +159,6 @@ bool calcStopPointAndInsertIndex(
}
return false;
}
-
-geometry_msgs::msg::Point getTrafficLightPosition(
- const lanelet::ConstLineStringOrPolygon3d & traffic_light)
-{
- if (!traffic_light.lineString()) {
- throw std::invalid_argument{"Traffic light is not LineString"};
- }
- geometry_msgs::msg::Point tl_center;
- auto traffic_light_ls = traffic_light.lineString().value();
- for (const auto & tl_point : traffic_light_ls) {
- tl_center.x += tl_point.x() / traffic_light_ls.size();
- tl_center.y += tl_point.y() / traffic_light_ls.size();
- tl_center.z += tl_point.z() / traffic_light_ls.size();
- }
- return tl_center;
-}
-autoware_auto_perception_msgs::msg::LookingTrafficSignal initializeTrafficSignal(
- const rclcpp::Time stamp)
-{
- autoware_auto_perception_msgs::msg::LookingTrafficSignal state;
- state.header.stamp = stamp;
- state.is_module_running = true;
- state.perception.has_state = false;
- state.result.has_state = false;
- return state;
-}
} // namespace
TrafficLightModule::TrafficLightModule(
@@ -197,7 +171,6 @@ TrafficLightModule::TrafficLightModule(
traffic_light_reg_elem_(traffic_light_reg_elem),
lane_(lane),
state_(State::APPROACH),
- input_(Input::PERCEPTION),
is_prev_state_stop_(false)
{
velocity_factor_.init(VelocityFactor::TRAFFIC_SIGNAL);
@@ -206,7 +179,6 @@ TrafficLightModule::TrafficLightModule(
bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason)
{
- looking_tl_state_ = initializeTrafficSignal(path->header.stamp);
debug_data_ = DebugData();
debug_data_.base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m;
first_stop_path_point_index_ = static_cast(path->points.size()) - 1;
@@ -217,9 +189,8 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
const auto & self_pose = planner_data_->current_odometry;
- // Get lanelet2 traffic lights and stop lines.
+ // Get lanelet2 stop lines.
lanelet::ConstLineString3d lanelet_stop_lines = *(traffic_light_reg_elem_.stopLine());
- lanelet::ConstLineStringsOrPolygons3d traffic_lights = traffic_light_reg_elem_.trafficLights();
// Calculate stop pose and insert index
Eigen::Vector2d stop_line_point{};
@@ -255,7 +226,7 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
first_ref_stop_path_point_index_ = stop_line_point_idx;
// Check if stop is coming.
- setSafe(!isStopSignal(traffic_lights));
+ setSafe(!isStopSignal());
if (isActivated()) {
is_prev_state_stop_ = false;
return true;
@@ -283,33 +254,27 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
return false;
}
-bool TrafficLightModule::isStopSignal(const lanelet::ConstLineStringsOrPolygons3d & traffic_lights)
+bool TrafficLightModule::isStopSignal()
{
- if (!updateTrafficSignal(traffic_lights)) {
+ if (!updateTrafficSignal()) {
return false;
}
- return looking_tl_state_.result.judge ==
- autoware_auto_perception_msgs::msg::TrafficSignalWithJudge::STOP;
+ return isTrafficSignalStop(looking_tl_state_);
}
-bool TrafficLightModule::updateTrafficSignal(
- const lanelet::ConstLineStringsOrPolygons3d & traffic_lights)
+bool TrafficLightModule::updateTrafficSignal()
{
- autoware_auto_perception_msgs::msg::TrafficSignalStamped tl_state_perception;
- bool found_perception = getHighestConfidenceTrafficSignal(traffic_lights, tl_state_perception);
+ TrafficSignal signal;
+ bool found_signal = findValidTrafficSignal(signal);
- if (!found_perception) {
+ if (!found_signal) {
// Don't stop when UNKNOWN or TIMEOUT as discussed at #508
- input_ = Input::NONE;
return false;
}
- if (found_perception) {
- looking_tl_state_.perception = generateTlStateWithJudgeFromTlState(tl_state_perception.signal);
- looking_tl_state_.result = looking_tl_state_.perception;
- input_ = Input::PERCEPTION;
- }
+ // Found signal associated with the lanelet
+ looking_tl_state_ = signal;
return true;
}
@@ -337,7 +302,7 @@ bool TrafficLightModule::isPassthrough(const double & signed_arc_length) const
const auto & enable_pass_judge = planner_param_.enable_pass_judge;
- if (enable_pass_judge && !stoppable && !is_prev_state_stop_ && input_ == Input::PERCEPTION) {
+ if (enable_pass_judge && !stoppable && !is_prev_state_stop_) {
// Cannot stop under acceleration and jerk limits.
// However, ego vehicle can't enter the intersection while the light is yellow.
// It is called dilemma zone. Make a stop decision to be safe.
@@ -359,10 +324,9 @@ bool TrafficLightModule::isPassthrough(const double & signed_arc_length) const
}
bool TrafficLightModule::isTrafficSignalStop(
- const autoware_auto_perception_msgs::msg::TrafficSignal & tl_state) const
+ const autoware_perception_msgs::msg::TrafficSignal & tl_state) const
{
- if (hasTrafficLightCircleColor(
- tl_state, autoware_auto_perception_msgs::msg::TrafficLight::GREEN)) {
+ if (hasTrafficLightCircleColor(tl_state, TrafficSignalElement::GREEN)) {
return false;
}
@@ -373,86 +337,46 @@ bool TrafficLightModule::isTrafficSignalStop(
}
if (
turn_direction == "right" &&
- hasTrafficLightShape(tl_state, autoware_auto_perception_msgs::msg::TrafficLight::RIGHT_ARROW)) {
+ hasTrafficLightShape(tl_state, TrafficSignalElement::RIGHT_ARROW)) {
return false;
}
if (
- turn_direction == "left" &&
- hasTrafficLightShape(tl_state, autoware_auto_perception_msgs::msg::TrafficLight::LEFT_ARROW)) {
+ turn_direction == "left" && hasTrafficLightShape(tl_state, TrafficSignalElement::LEFT_ARROW)) {
return false;
}
if (
turn_direction == "straight" &&
- hasTrafficLightShape(tl_state, autoware_auto_perception_msgs::msg::TrafficLight::UP_ARROW)) {
+ hasTrafficLightShape(tl_state, TrafficSignalElement::UP_ARROW)) {
return false;
}
return true;
}
-bool TrafficLightModule::getHighestConfidenceTrafficSignal(
- const lanelet::ConstLineStringsOrPolygons3d & traffic_lights,
- autoware_auto_perception_msgs::msg::TrafficSignalStamped & highest_confidence_tl_state)
+bool TrafficLightModule::findValidTrafficSignal(TrafficSignal & valid_traffic_signal)
{
- // search traffic light state
- bool found = false;
- double highest_confidence = 0.0;
- std::string reason;
- for (const auto & traffic_light : traffic_lights) {
- // traffic light must be linestrings
- if (!traffic_light.isLineString()) {
- reason = "NotLineString";
- continue;
- }
-
- const int id = static_cast(traffic_light).id();
- RCLCPP_DEBUG(logger_, "traffic light id: %d (on route)", id);
- const auto tl_state_stamped = planner_data_->getTrafficSignal(id);
- if (!tl_state_stamped) {
- reason = "TrafficSignalNotFound";
- continue;
- }
-
- const auto header = tl_state_stamped->header;
- const auto tl_state = tl_state_stamped->signal;
- if (!((clock_->now() - header.stamp).seconds() < planner_param_.tl_state_timeout)) {
- reason = "TimeOut";
- continue;
- }
-
- if (
- tl_state.lights.empty() ||
- tl_state.lights.front().color == autoware_auto_perception_msgs::msg::TrafficLight::UNKNOWN) {
- reason = "TrafficLightUnknown";
- continue;
- }
-
- if (highest_confidence < tl_state.lights.front().confidence) {
- highest_confidence = tl_state.lights.front().confidence;
- highest_confidence_tl_state = *tl_state_stamped;
- try {
- auto tl_position = getTrafficLightPosition(traffic_light);
- debug_data_.traffic_light_points.push_back(tl_position);
- debug_data_.highest_confidence_traffic_light_point = std::make_optional(tl_position);
- } catch (const std::invalid_argument & ex) {
- RCLCPP_WARN_STREAM(logger_, ex.what());
- continue;
- }
- found = true;
- }
+ // get traffic signal associated with the regulatory element id
+ const auto traffic_signal_stamped = planner_data_->getTrafficSignal(traffic_light_reg_elem_.id());
+ if (!traffic_signal_stamped) {
+ RCLCPP_WARN_THROTTLE(
+ logger_, *clock_, 5000 /* ms */,
+ "the traffic signal data associated with regulatory element id is not received");
+ return false;
}
- if (!found) {
- std::string not_found_traffic_ids{""};
- for (size_t i = 0; i < traffic_lights.size(); ++i) {
- const int id = static_cast(traffic_lights.at(i)).id();
- not_found_traffic_ids += (i != 0 ? "," : "") + std::to_string(id);
- }
+ // check if the traffic signal data is outdated
+ const auto is_traffic_signal_timeout =
+ (clock_->now() - traffic_signal_stamped->stamp).seconds() > planner_param_.tl_state_timeout;
+ if (is_traffic_signal_timeout) {
RCLCPP_WARN_THROTTLE(
- logger_, *clock_, 5000 /* ms */, "cannot find traffic light lamp state (%s) due to %s.",
- not_found_traffic_ids.c_str(), reason.c_str());
+ logger_, *clock_, 5000 /* ms */, "the received traffic signal data is outdated");
+ RCLCPP_WARN_STREAM_THROTTLE(
+ logger_, *clock_, 5000 /* ms */,
+ "time diff: " << (clock_->now() - traffic_signal_stamped->stamp).seconds());
return false;
}
+
+ valid_traffic_signal = traffic_signal_stamped->signal;
return true;
}
@@ -496,40 +420,24 @@ autoware_auto_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertStopP
}
bool TrafficLightModule::hasTrafficLightCircleColor(
- const autoware_auto_perception_msgs::msg::TrafficSignal & tl_state,
- const uint8_t & lamp_color) const
+ const autoware_perception_msgs::msg::TrafficSignal & tl_state, const uint8_t & lamp_color) const
{
- using autoware_auto_perception_msgs::msg::TrafficLight;
-
const auto it_lamp =
- std::find_if(tl_state.lights.begin(), tl_state.lights.end(), [&lamp_color](const auto & x) {
- return x.shape == TrafficLight::CIRCLE && x.color == lamp_color;
+ std::find_if(tl_state.elements.begin(), tl_state.elements.end(), [&lamp_color](const auto & x) {
+ return x.shape == TrafficSignalElement::CIRCLE && x.color == lamp_color;
});
- return it_lamp != tl_state.lights.end();
+ return it_lamp != tl_state.elements.end();
}
bool TrafficLightModule::hasTrafficLightShape(
- const autoware_auto_perception_msgs::msg::TrafficSignal & tl_state,
- const uint8_t & lamp_shape) const
+ const autoware_perception_msgs::msg::TrafficSignal & tl_state, const uint8_t & lamp_shape) const
{
const auto it_lamp = std::find_if(
- tl_state.lights.begin(), tl_state.lights.end(),
+ tl_state.elements.begin(), tl_state.elements.end(),
[&lamp_shape](const auto & x) { return x.shape == lamp_shape; });
- return it_lamp != tl_state.lights.end();
+ return it_lamp != tl_state.elements.end();
}
-autoware_auto_perception_msgs::msg::TrafficSignalWithJudge
-TrafficLightModule::generateTlStateWithJudgeFromTlState(
- const autoware_auto_perception_msgs::msg::TrafficSignal tl_state) const
-{
- autoware_auto_perception_msgs::msg::TrafficSignalWithJudge tl_state_with_judge;
- tl_state_with_judge.signal = tl_state;
- tl_state_with_judge.has_state = true;
- tl_state_with_judge.judge = isTrafficSignalStop(tl_state)
- ? autoware_auto_perception_msgs::msg::TrafficSignalWithJudge::STOP
- : autoware_auto_perception_msgs::msg::TrafficSignalWithJudge::GO;
- return tl_state_with_judge;
-}
} // namespace behavior_velocity_planner
diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_traffic_light_module/src/scene.hpp
index 99ece6cbca09d..a24db2c440e91 100644
--- a/planning/behavior_velocity_traffic_light_module/src/scene.hpp
+++ b/planning/behavior_velocity_traffic_light_module/src/scene.hpp
@@ -29,8 +29,6 @@
#include
#include
-#include
-
#include
#include
@@ -39,15 +37,15 @@ namespace behavior_velocity_planner
class TrafficLightModule : public SceneModuleInterface
{
public:
+ using TrafficSignal = autoware_perception_msgs::msg::TrafficSignal;
+ using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement;
enum class State { APPROACH, GO_OUT };
- enum class Input { PERCEPTION, NONE }; // EXTERNAL: FOA, V2X, etc.
struct DebugData
{
double base_link2front;
std::vector,
- autoware_auto_perception_msgs::msg::TrafficSignal>>
+ std::shared_ptr, autoware_perception_msgs::msg::TrafficSignal>>
tl_state;
std::vector stop_poses;
geometry_msgs::msg::Pose first_stop_pose;
@@ -77,10 +75,7 @@ class TrafficLightModule : public SceneModuleInterface
visualization_msgs::msg::MarkerArray createDebugMarkerArray() override;
motion_utils::VirtualWalls createVirtualWalls() override;
- inline autoware_auto_perception_msgs::msg::LookingTrafficSignal getTrafficSignal() const
- {
- return looking_tl_state_;
- }
+ inline TrafficSignal getTrafficSignal() const { return looking_tl_state_; }
inline State getTrafficLightModuleState() const { return state_; }
@@ -90,10 +85,9 @@ class TrafficLightModule : public SceneModuleInterface
}
private:
- bool isStopSignal(const lanelet::ConstLineStringsOrPolygons3d & traffic_lights);
+ bool isStopSignal();
- bool isTrafficSignalStop(
- const autoware_auto_perception_msgs::msg::TrafficSignal & tl_state) const;
+ bool isTrafficSignalStop(const TrafficSignal & tl_state) const;
autoware_auto_planning_msgs::msg::PathWithLaneId insertStopPose(
const autoware_auto_planning_msgs::msg::PathWithLaneId & input,
@@ -102,22 +96,13 @@ class TrafficLightModule : public SceneModuleInterface
bool isPassthrough(const double & signed_arc_length) const;
- bool hasTrafficLightCircleColor(
- const autoware_auto_perception_msgs::msg::TrafficSignal & tl_state,
- const uint8_t & lamp_color) const;
+ bool hasTrafficLightCircleColor(const TrafficSignal & tl_state, const uint8_t & lamp_color) const;
- bool hasTrafficLightShape(
- const autoware_auto_perception_msgs::msg::TrafficSignal & tl_state,
- const uint8_t & lamp_shape) const;
+ bool hasTrafficLightShape(const TrafficSignal & tl_state, const uint8_t & lamp_shape) const;
- bool getHighestConfidenceTrafficSignal(
- const lanelet::ConstLineStringsOrPolygons3d & traffic_lights,
- autoware_auto_perception_msgs::msg::TrafficSignalStamped & highest_confidence_tl_state);
+ bool findValidTrafficSignal(TrafficSignal & valid_traffic_signal);
- bool updateTrafficSignal(const lanelet::ConstLineStringsOrPolygons3d & traffic_lights);
-
- autoware_auto_perception_msgs::msg::TrafficSignalWithJudge generateTlStateWithJudgeFromTlState(
- const autoware_auto_perception_msgs::msg::TrafficSignal tl_state) const;
+ bool updateTrafficSignal();
// Lane id
const int64_t lane_id_;
@@ -129,9 +114,6 @@ class TrafficLightModule : public SceneModuleInterface
// State
State state_;
- // Input
- Input input_;
-
// Parameter
PlannerParam planner_param_;
@@ -144,7 +126,7 @@ class TrafficLightModule : public SceneModuleInterface
boost::optional first_ref_stop_path_point_index_;
// Traffic Light State
- autoware_auto_perception_msgs::msg::LookingTrafficSignal looking_tl_state_;
+ TrafficSignal looking_tl_state_;
};
} // namespace behavior_velocity_planner
diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py
index b45357c7bd8b2..9d8fa4a32a93d 100755
--- a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py
+++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py
@@ -93,11 +93,11 @@ def on_timer(self):
# traffic signals
if traffic_signals_msg:
- traffic_signals_msg.header.stamp = timestamp
+ traffic_signals_msg.stamp = timestamp
self.traffic_signals_pub.publish(traffic_signals_msg)
self.prev_traffic_signals_msg = traffic_signals_msg
elif self.prev_traffic_signals_msg:
- self.prev_traffic_signals_msg.header.stamp = timestamp
+ self.prev_traffic_signals_msg.stamp = timestamp
self.traffic_signals_pub.publish(self.prev_traffic_signals_msg)
def onPushed(self, event):
diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py
index a86a9ae9b2bb0..7774a8c82daf6 100644
--- a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py
+++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py
@@ -22,7 +22,7 @@
from autoware_auto_perception_msgs.msg import DetectedObjects
from autoware_auto_perception_msgs.msg import PredictedObjects
from autoware_auto_perception_msgs.msg import TrackedObjects
-from autoware_auto_perception_msgs.msg import TrafficSignalArray
+from autoware_perception_msgs.msg import TrafficSignalArray
from nav_msgs.msg import Odometry
import psutil
from rclpy.node import Node
diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py
index 4228d506d5bec..5344e622be38e 100755
--- a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py
+++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py
@@ -67,11 +67,11 @@ def on_timer(self):
# traffic signals
if traffic_signals_msg:
- traffic_signals_msg.header.stamp = timestamp
+ traffic_signals_msg.stamp = timestamp
self.traffic_signals_pub.publish(traffic_signals_msg)
self.prev_traffic_signals_msg = traffic_signals_msg
elif self.prev_traffic_signals_msg:
- self.prev_traffic_signals_msg.header.stamp = timestamp
+ self.prev_traffic_signals_msg.stamp = timestamp
self.traffic_signals_pub.publish(self.prev_traffic_signals_msg)
def find_nearest_ego_odom_by_observation(self, ego_pose):
diff --git a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp
index ddc304c99ea6a..c5a30be126661 100644
--- a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp
+++ b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp
@@ -38,11 +38,11 @@
#include
#include
#include
-#include
#include
#include
#include
#include
+#include
#include
#include
#include
@@ -77,10 +77,10 @@ namespace planning_test_utils
using autoware_adapi_v1_msgs::msg::OperationModeState;
using autoware_auto_mapping_msgs::msg::HADMapBin;
using autoware_auto_perception_msgs::msg::PredictedObjects;
-using autoware_auto_perception_msgs::msg::TrafficSignalArray;
using autoware_auto_planning_msgs::msg::Path;
using autoware_auto_planning_msgs::msg::PathWithLaneId;
using autoware_auto_planning_msgs::msg::Trajectory;
+using autoware_perception_msgs::msg::TrafficSignalArray;
using autoware_planning_msgs::msg::LaneletRoute;
using geometry_msgs::msg::AccelWithCovarianceStamped;
using geometry_msgs::msg::Point;
diff --git a/planning/planning_test_utils/package.xml b/planning/planning_test_utils/package.xml
index 72662f7ee7b76..23bfb2f44cb96 100644
--- a/planning/planning_test_utils/package.xml
+++ b/planning/planning_test_utils/package.xml
@@ -15,9 +15,9 @@
autoware_auto_control_msgs
autoware_auto_mapping_msgs
- autoware_auto_perception_msgs
autoware_auto_planning_msgs
autoware_auto_vehicle_msgs
+ autoware_perception_msgs
autoware_planning_msgs
component_interface_specs
component_interface_utils
diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp
index a797edaa34556..847c8db3b16a9 100644
--- a/planning/route_handler/include/route_handler/route_handler.hpp
+++ b/planning/route_handler/include/route_handler/route_handler.hpp
@@ -122,7 +122,8 @@ class RouteHandler
* @return vector of lanelet having same direction if true
*/
boost::optional getRightLanelet(
- const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false) const;
+ const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false,
+ const bool get_shoulder_lane = false) const;
/**
* @brief Check if same-direction lane is available at the left side of the lanelet
@@ -132,7 +133,8 @@ class RouteHandler
* @return vector of lanelet having same direction if true
*/
boost::optional getLeftLanelet(
- const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false) const;
+ const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false,
+ const bool get_shoulder_lane = false) const;
lanelet::ConstLanelets getNextLanelets(const lanelet::ConstLanelet & lanelet) const;
lanelet::ConstLanelets getPreviousLanelets(const lanelet::ConstLanelet & lanelet) const;
@@ -195,7 +197,8 @@ class RouteHandler
* @return vector of lanelet having same direction if true
*/
lanelet::ConstLanelet getMostRightLanelet(
- const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false) const;
+ const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false,
+ const bool get_shoulder_lane = false) const;
/**
* @brief Check if same-direction lane is available at the left side of the lanelet
@@ -205,7 +208,8 @@ class RouteHandler
* @return vector of lanelet having same direction if true
*/
lanelet::ConstLanelet getMostLeftLanelet(
- const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false) const;
+ const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false,
+ const bool get_shoulder_lane = false) const;
/**
* @brief Searches the furthest linestring to the right side of the lanelet
diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp
index 91f86ed0e454f..6a95434c81c23 100644
--- a/planning/route_handler/src/route_handler.cpp
+++ b/planning/route_handler/src/route_handler.cpp
@@ -528,7 +528,14 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequenceAfter(
while (rclcpp::ok() && length < min_length) {
lanelet::ConstLanelet next_lanelet;
if (!getNextLaneletWithinRoute(current_lanelet, &next_lanelet)) {
- break;
+ if (only_route_lanes) {
+ break;
+ }
+ const auto next_lanes = getNextLanelets(current_lanelet);
+ if (next_lanes.empty()) {
+ break;
+ }
+ next_lanelet = next_lanes.front();
}
// loop check
if (lanelet.id() == next_lanelet.id()) {
@@ -556,7 +563,14 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequenceUpTo(
while (rclcpp::ok() && length < min_length) {
lanelet::ConstLanelets candidate_lanelets;
if (!getPreviousLaneletsWithinRoute(current_lanelet, &candidate_lanelets)) {
- break;
+ if (only_route_lanes) {
+ break;
+ }
+ const auto prev_lanes = getPreviousLanelets(current_lanelet);
+ if (prev_lanes.empty()) {
+ break;
+ }
+ candidate_lanelets = prev_lanes;
}
// loop check
if (std::any_of(
@@ -954,7 +968,8 @@ bool RouteHandler::isBijectiveConnection(
}
boost::optional RouteHandler::getRightLanelet(
- const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const
+ const lanelet::ConstLanelet & lanelet, const bool enable_same_root,
+ const bool get_shoulder_lane) const
{
// right road lanelet of shoulder lanelet
if (isShoulderLanelet(lanelet)) {
@@ -966,6 +981,14 @@ boost::optional RouteHandler::getRightLanelet(
return boost::none;
}
+ // right shoulder lanelet
+ if (get_shoulder_lane) {
+ lanelet::ConstLanelet right_shoulder_lanelet;
+ if (getRightShoulderLanelet(lanelet, &right_shoulder_lanelet)) {
+ return right_shoulder_lanelet;
+ }
+ }
+
// routable lane
const auto & right_lane = routing_graph_ptr_->right(lanelet);
if (right_lane) {
@@ -1026,7 +1049,8 @@ bool RouteHandler::getLeftLaneletWithinRoute(
}
boost::optional RouteHandler::getLeftLanelet(
- const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const
+ const lanelet::ConstLanelet & lanelet, const bool enable_same_root,
+ const bool get_shoulder_lane) const
{
// left road lanelet of shoulder lanelet
if (isShoulderLanelet(lanelet)) {
@@ -1038,6 +1062,14 @@ boost::optional RouteHandler::getLeftLanelet(
return boost::none;
}
+ // left shoulder lanelet
+ if (get_shoulder_lane) {
+ lanelet::ConstLanelet left_shoulder_lanelet;
+ if (getLeftShoulderLanelet(lanelet, &left_shoulder_lanelet)) {
+ return left_shoulder_lanelet;
+ }
+ }
+
// routable lane
const auto & left_lane = routing_graph_ptr_->left(lanelet);
if (left_lane) {
@@ -1213,26 +1245,28 @@ lanelet::Lanelets RouteHandler::getLeftOppositeLanelets(const lanelet::ConstLane
}
lanelet::ConstLanelet RouteHandler::getMostRightLanelet(
- const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const
+ const lanelet::ConstLanelet & lanelet, const bool enable_same_root,
+ const bool get_shoulder_lane) const
{
// recursively compute the width of the lanes
- const auto & same = getRightLanelet(lanelet, enable_same_root);
+ const auto & same = getRightLanelet(lanelet, enable_same_root, get_shoulder_lane);
if (same) {
- return getMostRightLanelet(same.get(), enable_same_root);
+ return getMostRightLanelet(same.get(), enable_same_root, get_shoulder_lane);
}
return lanelet;
}
lanelet::ConstLanelet RouteHandler::getMostLeftLanelet(
- const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const
+ const lanelet::ConstLanelet & lanelet, const bool enable_same_root,
+ const bool get_shoulder_lane) const
{
// recursively compute the width of the lanes
- const auto & same = getLeftLanelet(lanelet, enable_same_root);
+ const auto & same = getLeftLanelet(lanelet, enable_same_root, get_shoulder_lane);
if (same) {
- return getMostLeftLanelet(same.get(), enable_same_root);
+ return getMostLeftLanelet(same.get(), enable_same_root, get_shoulder_lane);
}
return lanelet;
diff --git a/sensing/radar_static_pointcloud_filter/CMakeLists.txt b/sensing/radar_static_pointcloud_filter/CMakeLists.txt
index 1f08f7842cfdf..ecd33d3166b19 100644
--- a/sensing/radar_static_pointcloud_filter/CMakeLists.txt
+++ b/sensing/radar_static_pointcloud_filter/CMakeLists.txt
@@ -27,4 +27,5 @@ endif()
ament_auto_package(
INSTALL_TO_SHARE
launch
+ config
)
diff --git a/sensing/radar_static_pointcloud_filter/config/radar_static_pointcloud_filter.param.yaml b/sensing/radar_static_pointcloud_filter/config/radar_static_pointcloud_filter.param.yaml
new file mode 100644
index 0000000000000..a429f7a065ffe
--- /dev/null
+++ b/sensing/radar_static_pointcloud_filter/config/radar_static_pointcloud_filter.param.yaml
@@ -0,0 +1,17 @@
+# Copyright 2023 Foxconn, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+/**:
+ ros__parameters:
+ doppler_velocity_sd: 4.0
diff --git a/sensing/radar_static_pointcloud_filter/launch/radar_static_pointcloud_filter.launch.xml b/sensing/radar_static_pointcloud_filter/launch/radar_static_pointcloud_filter.launch.xml
index 08fdeee74f15a..b9491227837c5 100644
--- a/sensing/radar_static_pointcloud_filter/launch/radar_static_pointcloud_filter.launch.xml
+++ b/sensing/radar_static_pointcloud_filter/launch/radar_static_pointcloud_filter.launch.xml
@@ -3,13 +3,14 @@
-
+
+
-
+
diff --git a/sensing/radar_static_pointcloud_filter/schema/radar_static_pointcloud_filter.schema.json b/sensing/radar_static_pointcloud_filter/schema/radar_static_pointcloud_filter.schema.json
new file mode 100644
index 0000000000000..65340d889f62e
--- /dev/null
+++ b/sensing/radar_static_pointcloud_filter/schema/radar_static_pointcloud_filter.schema.json
@@ -0,0 +1,31 @@
+{
+ "$schema": "http://json-schema.org/draft-07/schema#",
+ "title": "Parameters for Radar Static Pointcloud Filter Node",
+ "type": "object",
+ "definitions": {
+ "radar_static_pointcloud_filter": {
+ "type": "object",
+ "properties": {
+ "doppler_velocity_sd": {
+ "type": "number",
+ "default": "4.0",
+ "minimum": 0.0,
+ "description": "Standard deviation for radar doppler velocity. [m/s]"
+ }
+ },
+ "required": ["doppler_velocity_sd"]
+ }
+ },
+ "properties": {
+ "/**": {
+ "type": "object",
+ "properties": {
+ "ros__parameters": {
+ "$ref": "#/definitions/radar_static_pointcloud_filter"
+ }
+ },
+ "required": ["ros__parameters"]
+ }
+ },
+ "required": ["/**"]
+}
diff --git a/sensing/radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node/radar_static_pointcloud_filter_node.cpp b/sensing/radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node/radar_static_pointcloud_filter_node.cpp
index c3550b0338675..772dcef753c11 100644
--- a/sensing/radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node/radar_static_pointcloud_filter_node.cpp
+++ b/sensing/radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node/radar_static_pointcloud_filter_node.cpp
@@ -1,4 +1,4 @@
-// Copyright 2022 TIER IV, Inc.
+// Copyright 2022-2023 Foxconn, TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
@@ -93,7 +93,7 @@ RadarStaticPointcloudFilterNode::RadarStaticPointcloudFilterNode(
std::bind(&RadarStaticPointcloudFilterNode::onSetParam, this, _1));
// Node Parameter
- node_param_.doppler_velocity_sd = declare_parameter("doppler_velocity_sd", 2.0);
+ node_param_.doppler_velocity_sd = declare_parameter("doppler_velocity_sd");
// Subscriber
transform_listener_ = std::make_shared(this);