Skip to content

Commit 22a0b40

Browse files
soblinkarishma1911
authored andcommitted
feat(tier4_autoware_utils): default QoS setting of polling subscriber (autowarefoundation#6976)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent f795bd8 commit 22a0b40

File tree

3 files changed

+71
-56
lines changed

3 files changed

+71
-56
lines changed

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

+18-16
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,8 @@
1717

1818
#include <rclcpp/rclcpp.hpp>
1919

20+
#include <memory>
21+
#include <stdexcept>
2022
#include <string>
2123

2224
namespace tier4_autoware_utils
@@ -27,37 +29,37 @@ class InterProcessPollingSubscriber
2729
{
2830
private:
2931
typename rclcpp::Subscription<T>::SharedPtr subscriber_;
30-
std::optional<T> data_;
32+
typename T::SharedPtr data_;
3133

3234
public:
33-
explicit InterProcessPollingSubscriber(rclcpp::Node * node, const std::string & topic_name)
35+
explicit InterProcessPollingSubscriber(
36+
rclcpp::Node * node, const std::string & topic_name, const rclcpp::QoS & qos = rclcpp::QoS{1})
3437
{
3538
auto noexec_callback_group =
3639
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false);
3740
auto noexec_subscription_options = rclcpp::SubscriptionOptions();
3841
noexec_subscription_options.callback_group = noexec_callback_group;
3942

4043
subscriber_ = node->create_subscription<T>(
41-
topic_name, rclcpp::QoS{1},
44+
topic_name, qos,
4245
[node]([[maybe_unused]] const typename T::ConstSharedPtr msg) { assert(false); },
4346
noexec_subscription_options);
44-
};
45-
bool updateLatestData()
46-
{
47-
rclcpp::MessageInfo message_info;
48-
T tmp;
49-
// The queue size (QoS) must be 1 to get the last message data.
50-
if (subscriber_->take(tmp, message_info)) {
51-
data_ = tmp;
47+
if (qos.get_rmw_qos_profile().depth > 1) {
48+
throw std::invalid_argument(
49+
"InterProcessPollingSubscriber will be used with depth > 1, which may cause inefficient "
50+
"serialization while updateLatestData()");
5251
}
53-
return data_.has_value();
5452
};
55-
const T & getData() const
53+
typename T::ConstSharedPtr takeData()
5654
{
57-
if (!data_.has_value()) {
58-
throw std::runtime_error("Bad_optional_access in class InterProcessPollingSubscriber");
55+
auto new_data = std::make_shared<T>();
56+
rclcpp::MessageInfo message_info;
57+
const bool success = subscriber_->take(*new_data, message_info);
58+
if (success) {
59+
data_ = new_data;
5960
}
60-
return data_.value();
61+
62+
return data_;
6163
};
6264
};
6365

planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp

+14-8
Original file line numberDiff line numberDiff line change
@@ -55,15 +55,19 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
5555
const std::vector<TrajectoryPoint> & traj_points,
5656
const vehicle_info_util::VehicleInfo & vehicle_info,
5757
const geometry_msgs::msg::Pose & current_ego_pose, const double lat_margin = 0.0) const;
58-
std::vector<Obstacle> convertToObstacles(const std::vector<TrajectoryPoint> & traj_points) const;
58+
std::vector<Obstacle> convertToObstacles(
59+
const Odometry & odometry, const PredictedObjects & objects,
60+
const std::vector<TrajectoryPoint> & traj_points) const;
5961
std::tuple<std::vector<StopObstacle>, std::vector<CruiseObstacle>, std::vector<SlowDownObstacle>>
6062
determineEgoBehaviorAgainstObstacles(
63+
const Odometry & odometry, const PredictedObjects & objecrts,
6164
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Obstacle> & obstacles);
6265
std::vector<TrajectoryPoint> decimateTrajectoryPoints(
63-
const std::vector<TrajectoryPoint> & traj_points) const;
66+
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points) const;
6467
std::optional<StopObstacle> createStopObstacle(
65-
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Polygon2d> & traj_polys,
66-
const Obstacle & obstacle, const double precise_lateral_dist) const;
68+
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points,
69+
const std::vector<Polygon2d> & traj_polys, const Obstacle & obstacle,
70+
const double precise_lateral_dist) const;
6771
bool isStopObstacle(const uint8_t label) const;
6872
bool isInsideCruiseObstacle(const uint8_t label) const;
6973
bool isOutsideCruiseObstacle(const uint8_t label) const;
@@ -88,12 +92,14 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
8892
bool isObstacleCrossing(
8993
const std::vector<TrajectoryPoint> & traj_points, const Obstacle & obstacle) const;
9094
double calcCollisionTimeMargin(
91-
const std::vector<PointWithStamp> & collision_points,
95+
const Odometry & odometry, const std::vector<PointWithStamp> & collision_points,
9296
const std::vector<TrajectoryPoint> & traj_points, const bool is_driving_forward) const;
9397
std::optional<SlowDownObstacle> createSlowDownObstacle(
94-
const std::vector<TrajectoryPoint> & traj_points, const Obstacle & obstacle,
95-
const double precise_lat_dist);
96-
PlannerData createPlannerData(const std::vector<TrajectoryPoint> & traj_points) const;
98+
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points,
99+
const Obstacle & obstacle, const double precise_lat_dist);
100+
PlannerData createPlannerData(
101+
const Odometry & odometry, const AccelWithCovarianceStamped & acc,
102+
const std::vector<TrajectoryPoint> & traj_points) const;
97103

98104
void checkConsistency(
99105
const rclcpp::Time & current_time, const PredictedObjects & predicted_objects,

planning/obstacle_cruise_planner/src/node.cpp

+39-32
Original file line numberDiff line numberDiff line change
@@ -484,12 +484,17 @@ rcl_interfaces::msg::SetParametersResult ObstacleCruisePlannerNode::onParam(
484484

485485
void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr msg)
486486
{
487-
if (
488-
!ego_odom_sub_.updateLatestData() || !objects_sub_.updateLatestData() ||
489-
!acc_sub_.updateLatestData()) {
487+
const auto ego_odom_ptr = ego_odom_sub_.takeData();
488+
const auto objects_ptr = objects_sub_.takeData();
489+
const auto acc_ptr = acc_sub_.takeData();
490+
if (!ego_odom_ptr || !objects_ptr || !acc_ptr) {
490491
return;
491492
}
492493

494+
const auto & ego_odom = *ego_odom_ptr;
495+
const auto & objects = *objects_ptr;
496+
const auto & acc = *acc_ptr;
497+
493498
const auto traj_points = motion_utils::convertToTrajectoryPointArray(*msg);
494499
// check if subscribed variables are ready
495500
if (traj_points.empty()) {
@@ -506,14 +511,14 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms
506511
// (1) with a proper label
507512
// (2) in front of ego
508513
// (3) not too far from trajectory
509-
const auto target_obstacles = convertToObstacles(traj_points);
514+
const auto target_obstacles = convertToObstacles(ego_odom, objects, traj_points);
510515

511516
// 2. Determine ego's behavior against each obstacle from stop, cruise and slow down.
512517
const auto & [stop_obstacles, cruise_obstacles, slow_down_obstacles] =
513-
determineEgoBehaviorAgainstObstacles(traj_points, target_obstacles);
518+
determineEgoBehaviorAgainstObstacles(ego_odom, objects, traj_points, target_obstacles);
514519

515520
// 3. Create data for planning
516-
const auto planner_data = createPlannerData(traj_points);
521+
const auto planner_data = createPlannerData(ego_odom, acc, traj_points);
517522

518523
// 4. Stop planning
519524
const auto stop_traj_points = planner_ptr_->generateStopTrajectory(planner_data, stop_obstacles);
@@ -629,15 +634,16 @@ std::vector<Polygon2d> ObstacleCruisePlannerNode::createOneStepPolygons(
629634
}
630635

631636
std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
637+
const Odometry & odometry, const PredictedObjects & objects,
632638
const std::vector<TrajectoryPoint> & traj_points) const
633639
{
634640
stop_watch_.tic(__func__);
635641

636-
const auto obj_stamp = rclcpp::Time(objects_sub_.getData().header.stamp);
642+
const auto obj_stamp = rclcpp::Time(objects.header.stamp);
637643
const auto & p = behavior_determination_param_;
638644

639645
std::vector<Obstacle> target_obstacles;
640-
for (const auto & predicted_object : objects_sub_.getData().objects) {
646+
for (const auto & predicted_object : objects.objects) {
641647
const auto & object_id =
642648
tier4_autoware_utils::toHexString(predicted_object.object_id).substr(0, 4);
643649
const auto & current_obstacle_pose =
@@ -655,8 +661,7 @@ std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
655661
}
656662

657663
// 2. Check if the obstacle is in front of the ego.
658-
const size_t ego_idx =
659-
ego_nearest_param_.findIndex(traj_points, ego_odom_sub_.getData().pose.pose);
664+
const size_t ego_idx = ego_nearest_param_.findIndex(traj_points, odometry.pose.pose);
660665
const auto ego_to_obstacle_distance =
661666
calcDistanceToFrontVehicle(traj_points, ego_idx, current_obstacle_pose.pose.position);
662667
if (!ego_to_obstacle_distance) {
@@ -745,14 +750,15 @@ bool ObstacleCruisePlannerNode::isFrontCollideObstacle(
745750

746751
std::tuple<std::vector<StopObstacle>, std::vector<CruiseObstacle>, std::vector<SlowDownObstacle>>
747752
ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles(
753+
const Odometry & odometry, const PredictedObjects & objects,
748754
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Obstacle> & obstacles)
749755
{
750756
stop_watch_.tic(__func__);
751757

752758
// calculated decimated trajectory points and trajectory polygon
753-
const auto decimated_traj_points = decimateTrajectoryPoints(traj_points);
759+
const auto decimated_traj_points = decimateTrajectoryPoints(odometry, traj_points);
754760
const auto decimated_traj_polys =
755-
createOneStepPolygons(decimated_traj_points, vehicle_info_, ego_odom_sub_.getData().pose.pose);
761+
createOneStepPolygons(decimated_traj_points, vehicle_info_, odometry.pose.pose);
756762
debug_data_ptr_->detection_polygons = decimated_traj_polys;
757763

758764
// determine ego's behavior from stop, cruise and slow down
@@ -777,14 +783,14 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles(
777783
cruise_obstacles.push_back(*cruise_obstacle);
778784
continue;
779785
}
780-
const auto stop_obstacle =
781-
createStopObstacle(decimated_traj_points, decimated_traj_polys, obstacle, precise_lat_dist);
786+
const auto stop_obstacle = createStopObstacle(
787+
odometry, decimated_traj_points, decimated_traj_polys, obstacle, precise_lat_dist);
782788
if (stop_obstacle) {
783789
stop_obstacles.push_back(*stop_obstacle);
784790
continue;
785791
}
786792
const auto slow_down_obstacle =
787-
createSlowDownObstacle(decimated_traj_points, obstacle, precise_lat_dist);
793+
createSlowDownObstacle(odometry, decimated_traj_points, obstacle, precise_lat_dist);
788794
if (slow_down_obstacle) {
789795
slow_down_obstacles.push_back(*slow_down_obstacle);
790796
continue;
@@ -810,7 +816,7 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles(
810816
slow_down_condition_counter_.removeCounterUnlessUpdated();
811817

812818
// Check target obstacles' consistency
813-
checkConsistency(objects_sub_.getData().header.stamp, objects_sub_.getData(), stop_obstacles);
819+
checkConsistency(objects.header.stamp, objects, stop_obstacles);
814820

815821
// update previous obstacles
816822
prev_stop_obstacles_ = stop_obstacles;
@@ -826,13 +832,12 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles(
826832
}
827833

828834
std::vector<TrajectoryPoint> ObstacleCruisePlannerNode::decimateTrajectoryPoints(
829-
const std::vector<TrajectoryPoint> & traj_points) const
835+
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points) const
830836
{
831837
const auto & p = behavior_determination_param_;
832838

833839
// trim trajectory
834-
const size_t ego_seg_idx =
835-
ego_nearest_param_.findSegmentIndex(traj_points, ego_odom_sub_.getData().pose.pose);
840+
const size_t ego_seg_idx = ego_nearest_param_.findSegmentIndex(traj_points, odometry.pose.pose);
836841
const size_t traj_start_point_idx = ego_seg_idx;
837842
const auto trimmed_traj_points =
838843
std::vector<TrajectoryPoint>(traj_points.begin() + traj_start_point_idx, traj_points.end());
@@ -1151,8 +1156,9 @@ ObstacleCruisePlannerNode::createCollisionPointsForOutsideCruiseObstacle(
11511156
}
11521157

11531158
std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
1154-
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Polygon2d> & traj_polys,
1155-
const Obstacle & obstacle, const double precise_lat_dist) const
1159+
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points,
1160+
const std::vector<Polygon2d> & traj_polys, const Obstacle & obstacle,
1161+
const double precise_lat_dist) const
11561162
{
11571163
const auto & p = behavior_determination_param_;
11581164
const auto & object_id = obstacle.uuid.substr(0, 4);
@@ -1203,7 +1209,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
12031209
}
12041210

12051211
const double collision_time_margin =
1206-
calcCollisionTimeMargin(collision_points, traj_points, is_driving_forward_);
1212+
calcCollisionTimeMargin(odometry, collision_points, traj_points, is_driving_forward_);
12071213
if (p.collision_time_margin < collision_time_margin) {
12081214
RCLCPP_INFO_EXPRESSION(
12091215
get_logger(), enable_debug_info_,
@@ -1216,7 +1222,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
12161222

12171223
// calculate collision points with trajectory with lateral stop margin
12181224
const auto traj_polys_with_lat_margin = createOneStepPolygons(
1219-
traj_points, vehicle_info_, ego_odom_sub_.getData().pose.pose, p.max_lat_margin_for_stop);
1225+
traj_points, vehicle_info_, odometry.pose.pose, p.max_lat_margin_for_stop);
12201226

12211227
const auto collision_point = polygon_utils::getCollisionPoint(
12221228
traj_points, traj_polys_with_lat_margin, obstacle, is_driving_forward_, vehicle_info_);
@@ -1231,8 +1237,8 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
12311237
}
12321238

12331239
std::optional<SlowDownObstacle> ObstacleCruisePlannerNode::createSlowDownObstacle(
1234-
const std::vector<TrajectoryPoint> & traj_points, const Obstacle & obstacle,
1235-
const double precise_lat_dist)
1240+
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points,
1241+
const Obstacle & obstacle, const double precise_lat_dist)
12361242
{
12371243
const auto & object_id = obstacle.uuid.substr(0, 4);
12381244
const auto & p = behavior_determination_param_;
@@ -1286,7 +1292,7 @@ std::optional<SlowDownObstacle> ObstacleCruisePlannerNode::createSlowDownObstacl
12861292
// calculate collision points with trajectory with lateral stop margin
12871293
// NOTE: For additional margin, hysteresis is not divided by two.
12881294
const auto traj_polys_with_lat_margin = createOneStepPolygons(
1289-
traj_points, vehicle_info_, ego_odom_sub_.getData().pose.pose,
1295+
traj_points, vehicle_info_, odometry.pose.pose,
12901296
p.max_lat_margin_for_slow_down + p.lat_hysteresis_margin_for_slow_down);
12911297

12921298
std::vector<Polygon2d> front_collision_polygons;
@@ -1446,11 +1452,11 @@ bool ObstacleCruisePlannerNode::isObstacleCrossing(
14461452
}
14471453

14481454
double ObstacleCruisePlannerNode::calcCollisionTimeMargin(
1449-
const std::vector<PointWithStamp> & collision_points,
1455+
const Odometry & odometry, const std::vector<PointWithStamp> & collision_points,
14501456
const std::vector<TrajectoryPoint> & traj_points, const bool is_driving_forward) const
14511457
{
1452-
const auto & ego_pose = ego_odom_sub_.getData().pose.pose;
1453-
const double ego_vel = ego_odom_sub_.getData().twist.twist.linear.x;
1458+
const auto & ego_pose = odometry.pose.pose;
1459+
const double ego_vel = odometry.twist.twist.linear.x;
14541460

14551461
const double time_to_reach_collision_point = [&]() {
14561462
const double abs_ego_offset = is_driving_forward
@@ -1477,14 +1483,15 @@ double ObstacleCruisePlannerNode::calcCollisionTimeMargin(
14771483
}
14781484

14791485
PlannerData ObstacleCruisePlannerNode::createPlannerData(
1486+
const Odometry & odometry, const AccelWithCovarianceStamped & acc,
14801487
const std::vector<TrajectoryPoint> & traj_points) const
14811488
{
14821489
PlannerData planner_data;
14831490
planner_data.current_time = now();
14841491
planner_data.traj_points = traj_points;
1485-
planner_data.ego_pose = ego_odom_sub_.getData().pose.pose;
1486-
planner_data.ego_vel = ego_odom_sub_.getData().twist.twist.linear.x;
1487-
planner_data.ego_acc = acc_sub_.getData().accel.accel.linear.x;
1492+
planner_data.ego_pose = odometry.pose.pose;
1493+
planner_data.ego_vel = odometry.twist.twist.linear.x;
1494+
planner_data.ego_acc = acc.accel.accel.linear.x;
14881495
planner_data.is_driving_forward = is_driving_forward_;
14891496
return planner_data;
14901497
}

0 commit comments

Comments
 (0)