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(map_based_prediction): consider crosswalks signals #6189

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
use_vehicle_acceleration: false # whether to consider current vehicle acceleration when predicting paths or not
speed_limit_multiplier: 1.5 # When using vehicle acceleration. Set vehicle's maximum predicted speed as the legal speed limit in that lanelet times this value
acceleration_exponential_half_life: 2.5 # [s] When using vehicle acceleration. The decaying acceleration model considers that the current vehicle acceleration will be halved after this many seconds
use_crosswalk_signal: true
# parameter for shoulder lane prediction
prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8

Expand All @@ -35,6 +36,6 @@
diff_dist_threshold_to_left_bound: 0.29 #[m]
diff_dist_threshold_to_right_bound: -0.29 #[m]
num_continuous_state_transition: 3
consider_only_routable_neighbours: false

Check warning on line 39 in perception/map_based_prediction/config/map_based_prediction.param.yaml

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (routable)

reference_path_resolution: 0.5 #[m]
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
#include <autoware_perception_msgs/msg/traffic_signal_array.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/twist.hpp>
Expand All @@ -42,6 +43,7 @@
#include <algorithm>
#include <deque>
#include <memory>
#include <optional>
#include <string>
#include <unordered_map>
#include <utility>
Expand Down Expand Up @@ -107,6 +109,9 @@ using autoware_auto_perception_msgs::msg::TrackedObject;
using autoware_auto_perception_msgs::msg::TrackedObjectKinematics;
using autoware_auto_perception_msgs::msg::TrackedObjects;
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
using autoware_perception_msgs::msg::TrafficSignal;
using autoware_perception_msgs::msg::TrafficSignalArray;
using autoware_perception_msgs::msg::TrafficSignalElement;
using tier4_autoware_utils::StopWatch;
using tier4_debug_msgs::msg::StringStamped;
using TrajectoryPoints = std::vector<TrajectoryPoint>;
Expand All @@ -122,6 +127,7 @@ class MapBasedPredictionNode : public rclcpp::Node
rclcpp::Publisher<StringStamped>::SharedPtr pub_calculation_time_;
rclcpp::Subscription<TrackedObjects>::SharedPtr sub_objects_;
rclcpp::Subscription<HADMapBin>::SharedPtr sub_map_;
rclcpp::Subscription<TrafficSignalArray>::SharedPtr sub_traffic_signals_;

// Object History
std::unordered_map<std::string, std::deque<ObjectData>> objects_history_;
Expand All @@ -131,6 +137,8 @@ class MapBasedPredictionNode : public rclcpp::Node
std::shared_ptr<lanelet::routing::RoutingGraph> routing_graph_ptr_;
std::shared_ptr<lanelet::traffic_rules::TrafficRules> traffic_rules_ptr_;

std::unordered_map<lanelet::Id, TrafficSignal> traffic_signal_id_map_;

// parameter update
OnSetParametersCallbackHandle::SharedPtr set_param_res_;
rcl_interfaces::msg::SetParametersResult onParam(
Expand Down Expand Up @@ -181,11 +189,14 @@ class MapBasedPredictionNode : public rclcpp::Node
double speed_limit_multiplier_;
double acceleration_exponential_half_life_;

bool use_crosswalk_signal_;

// Stop watch
StopWatch<std::chrono::milliseconds> stop_watch_;

// Member Functions
void mapCallback(const HADMapBin::ConstSharedPtr msg);
void trafficSignalsCallback(const TrafficSignalArray::ConstSharedPtr msg);
void objectsCallback(const TrackedObjects::ConstSharedPtr in_objects);

bool doesPathCrossAnyFence(const PredictedPath & predicted_path);
Expand Down Expand Up @@ -249,6 +260,8 @@ class MapBasedPredictionNode : public rclcpp::Node
const LaneletsData & lanelets_data);
bool isDuplicated(
const PredictedPath & predicted_path, const std::vector<PredictedPath> & predicted_paths);
std::optional<lanelet::Id> getTrafficSignalId(const lanelet::ConstLanelet & way_lanelet);
std::optional<TrafficSignalElement> getTrafficSignalElement(const lanelet::Id & id);

visualization_msgs::msg::Marker getDebugMarker(
const TrackedObject & object, const Maneuver & maneuver, const size_t obj_num);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,14 @@
<arg name="param_path" default="$(find-pkg-share map_based_prediction)/config/map_based_prediction.param.yaml"/>

<arg name="vector_map_topic" default="/map/vector_map"/>
<arg name="traffic_signals_topic" default="/perception/traffic_light_recognition/traffic_signals"/>
<arg name="output_topic" default="objects"/>
<arg name="input_topic" default="/perception/object_recognition/tracking/objects"/>

<node pkg="map_based_prediction" exec="map_based_prediction" name="map_based_prediction" output="screen">
<param from="$(var param_path)"/>
<remap from="/vector_map" to="$(var vector_map_topic)"/>
<remap from="/traffic_signals" to="$(var traffic_signals_topic)"/>
<remap from="~/output/objects" to="$(var output_topic)"/>
<remap from="~/input/objects" to="$(var input_topic)"/>
</node>
Expand Down
1 change: 1 addition & 0 deletions perception/map_based_prediction/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_auto_perception_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>interpolation</depend>
<depend>lanelet2_extension</depend>
<depend>libgoogle-glog-dev</depend>
Expand Down
57 changes: 57 additions & 0 deletions perception/map_based_prediction/src/map_based_prediction_node.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1643 to 1693, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check notice on line 1 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 6.39 to 6.30, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -788,6 +788,8 @@
acceleration_exponential_half_life_ =
declare_parameter<double>("acceleration_exponential_half_life");

use_crosswalk_signal_ = declare_parameter<bool>("use_crosswalk_signal");

Check warning on line 791 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L791

Added line #L791 was not covered by tests

path_generator_ = std::make_shared<PathGenerator>(
prediction_time_horizon_, lateral_control_time_horizon_, prediction_sampling_time_interval_,
min_crosswalk_user_velocity_);
Expand All @@ -801,6 +803,9 @@
sub_map_ = this->create_subscription<HADMapBin>(
"/vector_map", rclcpp::QoS{1}.transient_local(),
std::bind(&MapBasedPredictionNode::mapCallback, this, std::placeholders::_1));
sub_traffic_signals_ = this->create_subscription<TrafficSignalArray>(

Check warning on line 806 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L806

Added line #L806 was not covered by tests
"/traffic_signals", 1,
std::bind(&MapBasedPredictionNode::trafficSignalsCallback, this, std::placeholders::_1));

Check warning on line 808 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

MapBasedPredictionNode::MapBasedPredictionNode increases from 74 to 78 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

Check warning on line 808 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L808

Added line #L808 was not covered by tests

pub_objects_ = this->create_publisher<PredictedObjects>("~/output/objects", rclcpp::QoS{1});
pub_debug_markers_ =
Expand Down Expand Up @@ -872,6 +877,14 @@
crosswalks_.insert(crosswalks_.end(), walkways.begin(), walkways.end());
}

void MapBasedPredictionNode::trafficSignalsCallback(const TrafficSignalArray::ConstSharedPtr msg)

Check warning on line 880 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L880

Added line #L880 was not covered by tests
{
traffic_signal_id_map_.clear();
for (const auto & signal : msg->signals) {
traffic_signal_id_map_[signal.traffic_signal_id] = signal;

Check warning on line 884 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L883-L884

Added lines #L883 - L884 were not covered by tests
}
}

Check warning on line 886 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L886

Added line #L886 was not covered by tests

void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPtr in_objects)
{
stop_watch_.tic();
Expand Down Expand Up @@ -1218,6 +1231,18 @@
}
// try to find the edge points for all crosswalks and generate path to the crosswalk edge
for (const auto & crosswalk : crosswalks_) {
const auto crosswalk_signal_id_opt = getTrafficSignalId(crosswalk);
if (crosswalk_signal_id_opt.has_value() && use_crosswalk_signal_) {
const auto signal_color = [&] {
const auto elem_opt = getTrafficSignalElement(crosswalk_signal_id_opt.value());
return elem_opt ? elem_opt.value().color : TrafficSignalElement::UNKNOWN;
}();

Check warning on line 1239 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L1234-L1239

Added lines #L1234 - L1239 were not covered by tests

if (signal_color == TrafficSignalElement::RED) {
continue;

Check warning on line 1242 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L1241-L1242

Added lines #L1241 - L1242 were not covered by tests
}
}

Check warning on line 1245 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser increases in cyclomatic complexity from 21 to 26, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
const auto edge_points = getCrosswalkEdgePoints(crosswalk);

const auto reachable_first = hasPotentialToReach(
Expand Down Expand Up @@ -2211,6 +2236,38 @@

return false;
}

std::optional<lanelet::Id> MapBasedPredictionNode::getTrafficSignalId(

Check warning on line 2240 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L2240

Added line #L2240 was not covered by tests
const lanelet::ConstLanelet & way_lanelet)
{
const auto traffic_light_reg_elems =
way_lanelet.regulatoryElementsAs<const lanelet::TrafficLight>();
if (traffic_light_reg_elems.empty()) {
return std::nullopt;
} else if (traffic_light_reg_elems.size() > 1) {
RCLCPP_ERROR(

Check warning on line 2248 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L2245-L2248

Added lines #L2245 - L2248 were not covered by tests
get_logger(),
"[Map Based Prediction]: "
"Multiple regulatory elements as TrafficLight are defined to one lanelet object.");
}
return traffic_light_reg_elems.front()->id();
}

Check warning on line 2254 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L2253-L2254

Added lines #L2253 - L2254 were not covered by tests

std::optional<TrafficSignalElement> MapBasedPredictionNode::getTrafficSignalElement(

Check warning on line 2256 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L2256

Added line #L2256 was not covered by tests
const lanelet::Id & id)
{
if (traffic_signal_id_map_.count(id) != 0) {
const auto & signal_elements = traffic_signal_id_map_.at(id).elements;
if (signal_elements.size() > 1) {
RCLCPP_ERROR(

Check warning on line 2262 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L2261-L2262

Added lines #L2261 - L2262 were not covered by tests
get_logger(), "[Map Based Prediction]: Multiple TrafficSignalElement_ are received.");
} else if (!signal_elements.empty()) {
return signal_elements.front();

Check warning on line 2265 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L2264-L2265

Added lines #L2264 - L2265 were not covered by tests
}
}
return std::nullopt;

Check warning on line 2268 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/map_based_prediction/src/map_based_prediction_node.cpp#L2268

Added line #L2268 was not covered by tests
}

} // namespace map_based_prediction

#include <rclcpp_components/register_node_macro.hpp>
Expand Down
Loading