Skip to content

Commit

Permalink
consider the crosswalks signals
Browse files Browse the repository at this point in the history
Signed-off-by: Yuki Takagi <[email protected]>
  • Loading branch information
yuki-takagi-66 committed Jan 26, 2024
1 parent f0b8555 commit 56cf8f6
Show file tree
Hide file tree
Showing 4 changed files with 59 additions and 0 deletions.
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 @@ -186,6 +194,7 @@ class MapBasedPredictionNode : public rclcpp::Node

// 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 +258,7 @@ 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);

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
46 changes: 46 additions & 0 deletions perception/map_based_prediction/src/map_based_prediction_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -801,6 +801,9 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
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 804 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#L804

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

Check warning on line 806 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 77 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 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

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

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

Check warning on line 878 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#L878

Added line #L878 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 882 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#L881-L882

Added lines #L881 - L882 were not covered by tests
}
}

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#L884

Added line #L884 was not covered by tests

void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPtr in_objects)
{
stop_watch_.tic();
Expand Down Expand Up @@ -1218,6 +1229,23 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
}
// 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()) {

Check warning on line 1233 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#L1232-L1233

Added lines #L1232 - L1233 were not covered by tests
// If the crosswalk has traffic light, do something.
if (traffic_signal_id_map.count(crosswalk_signal_id_opt.value()) != 0) {
const auto & signal_elements =
traffic_signal_id_map.at(crosswalk_signal_id_opt.value()).elements;
if (signal_elements.size() > 1) {
RCLCPP_ERROR(

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#L1238-L1239

Added lines #L1238 - L1239 were not covered by tests
get_logger(), "[Map Based Prediction]: Multiple TrafficSignalElement_ are recieved.");

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

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (recieved)
} else if (
!signal_elements.empty() && signal_elements.front().color == TrafficSignalElement::RED) {
continue;

Check warning on line 1243 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-L1243

Added lines #L1241 - L1243 were not covered by tests
}
}
// TODO(yuki takagi): If a flag is setted, wait for timeout while the pedestrian is stopping.
}

Check warning on line 1248 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 27, 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.

Check warning on line 1248 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)

❌ New issue: Deep, Nested Complexity

MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser has a nested complexity depth of 4, threshold = 4. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.
const auto edge_points = getCrosswalkEdgePoints(crosswalk);

const auto reachable_first = hasPotentialToReach(
Expand Down Expand Up @@ -2211,6 +2239,24 @@ bool MapBasedPredictionNode::isDuplicated(

return false;
}

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

Check warning on line 2243 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#L2243

Added line #L2243 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 2251 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#L2248-L2251

Added lines #L2248 - L2251 were not covered by tests
get_logger(),
"[Map Based Prediction]: "
"Multiple regulatory elements as TrafficLight are defined to one lanelet object.");
return std::nullopt; // Is it appropriate?

Check warning on line 2255 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#L2255

Added line #L2255 was not covered by tests
}
return traffic_light_reg_elems.front()->id();
}

Check warning on line 2258 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#L2257-L2258

Added lines #L2257 - L2258 were not covered by tests

} // namespace map_based_prediction

#include <rclcpp_components/register_node_macro.hpp>
Expand Down

0 comments on commit 56cf8f6

Please sign in to comment.