Skip to content

Commit cb557db

Browse files
authored
feat(tier4_autoware_utils): add the API to check if taken data is stale (autowarefoundation#7404)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent c89cd08 commit cb557db

File tree

2 files changed

+26
-1
lines changed

2 files changed

+26
-1
lines changed

common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp

+25
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,12 @@ class InterProcessPollingSubscriber<T, N, typename std::enable_if<N == 1>::type>
6464
"serialization while updateLatestData()");
6565
}
6666
};
67+
/*
68+
* @brief take and return the latest data from DDS queue if such data existed, otherwise return
69+
* previous taken data("stale" data)
70+
* @note if you want to ignore "stale" data, you should use takeNewData()
71+
* instead
72+
*/
6773
typename T::ConstSharedPtr takeData()
6874
{
6975
auto new_data = std::make_shared<T>();
@@ -75,6 +81,25 @@ class InterProcessPollingSubscriber<T, N, typename std::enable_if<N == 1>::type>
7581

7682
return data_;
7783
};
84+
85+
/*
86+
* @brief take and return the latest data from DDS queue if such data existed, otherwise return
87+
* nullptr instead
88+
* @note this API allows you to avoid redundant computation on the taken data which is unchanged
89+
* since the previous cycle
90+
*/
91+
typename T::ConstSharedPtr takeNewData()
92+
{
93+
auto new_data = std::make_shared<T>();
94+
rclcpp::MessageInfo message_info;
95+
const bool success = subscriber_->take(*new_data, message_info);
96+
if (success) {
97+
data_ = new_data;
98+
return data_;
99+
} else {
100+
return nullptr;
101+
}
102+
}
78103
};
79104

80105
template <typename T, int N>

control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -259,7 +259,7 @@ void LaneDepartureCheckerNode::onTimer()
259259
reference_trajectory_ = sub_reference_trajectory_.takeData();
260260
predicted_trajectory_ = sub_predicted_trajectory_.takeData();
261261

262-
const auto lanelet_map_bin_msg = sub_lanelet_map_bin_.takeData();
262+
const auto lanelet_map_bin_msg = sub_lanelet_map_bin_.takeNewData();
263263
if (lanelet_map_bin_msg) {
264264
lanelet_map_ = std::make_shared<lanelet::LaneletMap>();
265265
lanelet::utils::conversion::fromBinMsg(

0 commit comments

Comments
 (0)