Skip to content

Commit 1c54d43

Browse files
feat(map based prediction, crosswalk)!: transplantation of pedestrians' behavior prediction against green signal (#6338)
* pedestrians' intention estimation feature against the green signal * delete the reimplimented feature * sync params * update docs --------- Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp>
1 parent 5b18c25 commit 1c54d43

File tree

8 files changed

+163
-81
lines changed

8 files changed

+163
-81
lines changed

perception/map_based_prediction/README.md

+10-4
Original file line numberDiff line numberDiff line change
@@ -191,6 +191,11 @@ This module treats **Pedestrians** and **Bicycles** as objects using the crosswa
191191

192192
If there are a reachable crosswalk entry points within the `prediction_time_horizon` and the objects satisfies above condition, this module outputs additional predicted path to cross the opposite side via the crosswalk entry point.
193193

194+
This module takes into account the corresponding traffic light information.
195+
When RED signal is indicated, we assume the target object will not walk across.
196+
In additon, if the target object is stopping (not moving) against GREEN signal, we assume the target object will not walk across either.
197+
This prediction comes from the assumption that the object should move if the traffic light is green and the object is intended to cross.
198+
194199
<div align="center">
195200
<img src="images/outside_road.svg" width=90%>
196201
</div>
@@ -205,10 +210,11 @@ If the target object is inside the road or crosswalk, this module outputs one or
205210

206211
### Input
207212

208-
| Name | Type | Description |
209-
| -------------------------------------------------- | ---------------------------------------------------- | ---------------------------------------- |
210-
| `~/perception/object_recognition/tracking/objects` | `autoware_auto_perception_msgs::msg::TrackedObjects` | tracking objects without predicted path. |
211-
| `~/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | binary data of Lanelet2 Map. |
213+
| Name | Type | Description |
214+
| -------------------------------------------------------- | ---------------------------------------------------- | ---------------------------------------------------------- |
215+
| `~/perception/object_recognition/tracking/objects` | `autoware_auto_perception_msgs::msg::TrackedObjects` | tracking objects without predicted path. |
216+
| `~/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | binary data of Lanelet2 Map. |
217+
| '~/perception/traffic_light_recognition/traffic_signals' | 'autoware_perception_msgs::msg::TrafficSignalArray;' | rearranged information on the corresponding traffic lights |
212218

213219
### Output
214220

perception/map_based_prediction/config/map_based_prediction.param.yaml

+6-1
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,12 @@
1919
use_vehicle_acceleration: false # whether to consider current vehicle acceleration when predicting paths or not
2020
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
2121
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
22-
use_crosswalk_signal: true
22+
crosswalk_with_signal:
23+
use_crosswalk_signal: true
24+
threshold_velocity_assumed_as_stopping: 0.25 # [m/s] velocity threshold for the module to judge whether the objects is stopped
25+
# If the pedestrian does not move for X seconds against green signal, the module judge that the pedestrian has no intention to walk.
26+
distance_set_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order, keys of map
27+
timeout_set_for_no_intention_to_walk: [1.0, 0.0] # [s] values of map
2328
# parameter for shoulder lane prediction
2429
prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8
2530

perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp

+10-1
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@
4242

4343
#include <algorithm>
4444
#include <deque>
45+
#include <map>
4546
#include <memory>
4647
#include <optional>
4748
#include <string>
@@ -131,6 +132,7 @@ class MapBasedPredictionNode : public rclcpp::Node
131132

132133
// Object History
133134
std::unordered_map<std::string, std::deque<ObjectData>> objects_history_;
135+
std::map<std::pair<std::string, lanelet::Id>, rclcpp::Time> stopped_times_against_green_;
134136

135137
// Lanelet Map Pointers
136138
std::shared_ptr<lanelet::LaneletMap> lanelet_map_ptr_;
@@ -190,6 +192,9 @@ class MapBasedPredictionNode : public rclcpp::Node
190192
double acceleration_exponential_half_life_;
191193

192194
bool use_crosswalk_signal_;
195+
double threshold_velocity_assumed_as_stopping_;
196+
std::vector<double> distance_set_for_no_intention_to_walk_;
197+
std::vector<double> timeout_set_for_no_intention_to_walk_;
193198

194199
// Stop watch
195200
StopWatch<std::chrono::milliseconds> stop_watch_;
@@ -214,7 +219,8 @@ class MapBasedPredictionNode : public rclcpp::Node
214219

215220
PredictedObject getPredictedObjectAsCrosswalkUser(const TrackedObject & object);
216221

217-
void removeOldObjectsHistory(const double current_time);
222+
void removeOldObjectsHistory(
223+
const double current_time, const TrackedObjects::ConstSharedPtr in_objects);
218224

219225
LaneletsData getCurrentLanelets(const TrackedObject & object);
220226
bool checkCloseLaneletCondition(
@@ -262,6 +268,9 @@ class MapBasedPredictionNode : public rclcpp::Node
262268
const PredictedPath & predicted_path, const std::vector<PredictedPath> & predicted_paths);
263269
std::optional<lanelet::Id> getTrafficSignalId(const lanelet::ConstLanelet & way_lanelet);
264270
std::optional<TrafficSignalElement> getTrafficSignalElement(const lanelet::Id & id);
271+
bool calcIntentionToCrossWithTrafficSgnal(
272+
const TrackedObject & object, const lanelet::ConstLanelet & crosswalk,
273+
const lanelet::Id & signal_id);
265274

266275
visualization_msgs::msg::Marker getDebugMarker(
267276
const TrackedObject & object, const Maneuver & maneuver, const size_t obj_num);

perception/map_based_prediction/src/map_based_prediction_node.cpp

+89-9
Original file line numberDiff line numberDiff line change
@@ -788,7 +788,13 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
788788
acceleration_exponential_half_life_ =
789789
declare_parameter<double>("acceleration_exponential_half_life");
790790

791-
use_crosswalk_signal_ = declare_parameter<bool>("use_crosswalk_signal");
791+
use_crosswalk_signal_ = declare_parameter<bool>("crosswalk_with_signal.use_crosswalk_signal");
792+
threshold_velocity_assumed_as_stopping_ =
793+
declare_parameter<double>("crosswalk_with_signal.threshold_velocity_assumed_as_stopping");
794+
distance_set_for_no_intention_to_walk_ = declare_parameter<std::vector<double>>(
795+
"crosswalk_with_signal.distance_set_for_no_intention_to_walk");
796+
timeout_set_for_no_intention_to_walk_ = declare_parameter<std::vector<double>>(
797+
"crosswalk_with_signal.timeout_set_for_no_intention_to_walk");
792798

793799
path_generator_ = std::make_shared<PathGenerator>(
794800
prediction_time_horizon_, lateral_control_time_horizon_, prediction_sampling_time_interval_,
@@ -912,7 +918,7 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt
912918

913919
// Remove old objects information in object history
914920
const double objects_detected_time = rclcpp::Time(in_objects->header.stamp).seconds();
915-
removeOldObjectsHistory(objects_detected_time);
921+
removeOldObjectsHistory(objects_detected_time, in_objects);
916922

917923
// result output
918924
PredictedObjects output;
@@ -1229,16 +1235,13 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
12291235
}
12301236
}
12311237
}
1238+
12321239
// try to find the edge points for all crosswalks and generate path to the crosswalk edge
12331240
for (const auto & crosswalk : crosswalks_) {
12341241
const auto crosswalk_signal_id_opt = getTrafficSignalId(crosswalk);
12351242
if (crosswalk_signal_id_opt.has_value() && use_crosswalk_signal_) {
1236-
const auto signal_color = [&] {
1237-
const auto elem_opt = getTrafficSignalElement(crosswalk_signal_id_opt.value());
1238-
return elem_opt ? elem_opt.value().color : TrafficSignalElement::UNKNOWN;
1239-
}();
1240-
1241-
if (signal_color == TrafficSignalElement::RED) {
1243+
if (!calcIntentionToCrossWithTrafficSgnal(
1244+
object, crosswalk, crosswalk_signal_id_opt.value())) {
12421245
continue;
12431246
}
12441247
}
@@ -1330,7 +1333,8 @@ void MapBasedPredictionNode::updateObjectData(TrackedObject & object)
13301333
return;
13311334
}
13321335

1333-
void MapBasedPredictionNode::removeOldObjectsHistory(const double current_time)
1336+
void MapBasedPredictionNode::removeOldObjectsHistory(
1337+
const double current_time, const TrackedObjects::ConstSharedPtr in_objects)
13341338
{
13351339
std::vector<std::string> invalid_object_id;
13361340
for (auto iter = objects_history_.begin(); iter != objects_history_.end(); ++iter) {
@@ -1371,6 +1375,19 @@ void MapBasedPredictionNode::removeOldObjectsHistory(const double current_time)
13711375
for (const auto & key : invalid_object_id) {
13721376
objects_history_.erase(key);
13731377
}
1378+
1379+
for (auto it = stopped_times_against_green_.begin(); it != stopped_times_against_green_.end();) {
1380+
const bool isDisappeared = std::none_of(
1381+
in_objects->objects.begin(), in_objects->objects.end(),
1382+
[&it](autoware_auto_perception_msgs::msg::TrackedObject obj) {
1383+
return tier4_autoware_utils::toHexString(obj.object_id) == it->first.first;
1384+
});
1385+
if (isDisappeared) {
1386+
it = stopped_times_against_green_.erase(it);
1387+
} else {
1388+
++it;
1389+
}
1390+
}
13741391
}
13751392

13761393
LaneletsData MapBasedPredictionNode::getCurrentLanelets(const TrackedObject & object)
@@ -2268,6 +2285,69 @@ std::optional<TrafficSignalElement> MapBasedPredictionNode::getTrafficSignalElem
22682285
return std::nullopt;
22692286
}
22702287

2288+
bool MapBasedPredictionNode::calcIntentionToCrossWithTrafficSgnal(
2289+
const TrackedObject & object, const lanelet::ConstLanelet & crosswalk,
2290+
const lanelet::Id & signal_id)
2291+
{
2292+
const auto signal_color = [&] {
2293+
const auto elem_opt = getTrafficSignalElement(signal_id);
2294+
return elem_opt ? elem_opt.value().color : TrafficSignalElement::UNKNOWN;
2295+
}();
2296+
2297+
const auto key = std::make_pair(tier4_autoware_utils::toHexString(object.object_id), signal_id);
2298+
if (
2299+
signal_color == TrafficSignalElement::GREEN &&
2300+
tier4_autoware_utils::calcNorm(object.kinematics.twist_with_covariance.twist.linear) <
2301+
threshold_velocity_assumed_as_stopping_) {
2302+
stopped_times_against_green_.try_emplace(key, this->get_clock()->now());
2303+
2304+
const auto timeout_no_intention_to_walk = [&]() {
2305+
auto InterpolateMap = [](
2306+
const std::vector<double> & key_set,
2307+
const std::vector<double> & value_set, const double query) {
2308+
if (query <= key_set.front()) {
2309+
return value_set.front();
2310+
} else if (query >= key_set.back()) {
2311+
return value_set.back();
2312+
}
2313+
for (size_t i = 0; i < key_set.size() - 1; ++i) {
2314+
if (key_set.at(i) <= query && query <= key_set.at(i + 1)) {
2315+
auto ratio =
2316+
(query - key_set.at(i)) / std::max(key_set.at(i + 1) - key_set.at(i), 1.0e-5);
2317+
ratio = std::clamp(ratio, 0.0, 1.0);
2318+
return value_set.at(i) + ratio * (value_set.at(i + 1) - value_set.at(i));
2319+
}
2320+
}
2321+
return value_set.back();
2322+
};
2323+
2324+
const auto obj_position = object.kinematics.pose_with_covariance.pose.position;
2325+
const double distance_to_crosswalk = boost::geometry::distance(
2326+
crosswalk.polygon2d().basicPolygon(),
2327+
lanelet::BasicPoint2d(obj_position.x, obj_position.y));
2328+
return InterpolateMap(
2329+
distance_set_for_no_intention_to_walk_, timeout_set_for_no_intention_to_walk_,
2330+
distance_to_crosswalk);
2331+
}();
2332+
2333+
if (
2334+
(this->get_clock()->now() - stopped_times_against_green_.at(key)).seconds() >
2335+
timeout_no_intention_to_walk) {
2336+
return false;
2337+
}
2338+
2339+
} else {
2340+
stopped_times_against_green_.erase(key);
2341+
// If the pedestrian disappears, another function erases the old data.
2342+
}
2343+
2344+
if (signal_color == TrafficSignalElement::RED) {
2345+
return false;
2346+
}
2347+
2348+
return true;
2349+
}
2350+
22712351
} // namespace map_based_prediction
22722352

22732353
#include <rclcpp_components/register_node_macro.hpp>

0 commit comments

Comments
 (0)