Skip to content

Commit cb38bda

Browse files
yuki-takagi-66pre-commit-ci[bot]mkuri
authored
feat(obstacle_cruise): pseudo occlusion (#1258)
Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Makoto Kurihara <mkuri8m@gmail.com>
1 parent 8c29188 commit cb38bda

File tree

5 files changed

+131
-2
lines changed

5 files changed

+131
-2
lines changed

launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml

+51
Original file line numberDiff line numberDiff line change
@@ -125,6 +125,7 @@
125125
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
126126
<remap from="~/input/acceleration" to="/localization/acceleration"/>
127127
<remap from="~/input/objects" to="/perception/object_recognition/objects"/>
128+
<remap from="~/input/vector_map" to="/map/vector_map"/>
128129
<remap from="~/output/trajectory" to="$(var interface_output_topic)"/>
129130
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>
130131
<remap from="~/output/velocity_limit" to="/planning/scenario_planning/max_velocity_candidates"/>
@@ -165,6 +166,56 @@
165166
</load_composable_node>
166167
</group>
167168

169+
<!-- First Obstacle Cruise (original) -->
170+
<group if="$(eval &quot;'$(var motion_stop_planner_type)' == 'obstacle_cruise_planner_with_pseudo_occlusion'&quot;)">
171+
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
172+
<composable_node pkg="obstacle_cruise_planner" plugin="motion_planning::ObstacleCruisePlannerNode" name="obstacle_cruise_planner" namespace="">
173+
<!-- topic remap -->
174+
<remap from="~/input/trajectory" to="obstacle_velocity_limiter/trajectory"/>
175+
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
176+
<remap from="~/input/acceleration" to="/localization/acceleration"/>
177+
<remap from="~/input/objects" to="/perception/object_recognition/objects"/>
178+
<remap from="~/input/vector_map" to="/map/vector_map"/>
179+
<remap from="~/output/trajectory" to="obstacle_cruise/trajectory"/>
180+
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>
181+
<remap from="~/output/velocity_limit" to="/planning/scenario_planning/max_velocity_candidates"/>
182+
<remap from="~/output/clear_velocity_limit" to="/planning/scenario_planning/clear_velocity_limit"/>
183+
<!-- params -->
184+
<param from="$(var common_param_path)"/>
185+
<param from="$(var vehicle_param_file)"/>
186+
<param from="$(var nearest_search_param_path)"/>
187+
<param from="$(var obstacle_cruise_planner_param_path)"/>
188+
<!-- composable node config -->
189+
<extra_arg name="use_intra_process_comms" value="false"/>
190+
</composable_node>
191+
</load_composable_node>
192+
</group>
193+
194+
<!-- Second Obstacle Cruise (pseudo occlusion)-->
195+
<group if="$(eval &quot;'$(var motion_stop_planner_type)' == 'obstacle_cruise_planner_with_pseudo_occlusion'&quot;)">
196+
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
197+
<composable_node pkg="obstacle_cruise_planner" plugin="motion_planning::ObstacleCruisePlannerNode" name="obstacle_cruise_planner_pseudo_occlusion" namespace="">
198+
<!-- topic remap -->
199+
<remap from="~/input/trajectory" to="obstacle_cruise/trajectory"/>
200+
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
201+
<remap from="~/input/acceleration" to="/localization/acceleration"/>
202+
<remap from="~/input/objects" to="/perception/object_recognition/objects"/>
203+
<remap from="~/input/vector_map" to="/map/vector_map"/>
204+
<remap from="~/output/trajectory" to="$(var interface_output_topic)"/>
205+
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>
206+
<remap from="~/output/velocity_limit" to="/planning/scenario_planning/max_velocity_candidates"/>
207+
<remap from="~/output/clear_velocity_limit" to="/planning/scenario_planning/clear_velocity_limit"/>
208+
<!-- params -->
209+
<param from="$(var common_param_path)"/>
210+
<param from="$(var vehicle_param_file)"/>
211+
<param from="$(var nearest_search_param_path)"/>
212+
<param from="$(var obstacle_cruise_planner_pseudo_occlusion_param_path)"/>
213+
<!-- composable node config -->
214+
<extra_arg name="use_intra_process_comms" value="false"/>
215+
</composable_node>
216+
</load_composable_node>
217+
</group>
218+
168219
<group if="$(eval &quot;'$(var motion_stop_planner_type)' == 'none'&quot;)">
169220
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
170221
<composable_node pkg="topic_tools" plugin="topic_tools::RelayNode" name="obstacle_stop_relay" namespace="">

planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp

+8
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include "obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp"
2020
#include "obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp"
2121
#include "obstacle_cruise_planner/type_alias.hpp"
22+
#include "route_handler/route_handler.hpp"
2223
#include "signal_processing/lowpass_filter_1d.hpp"
2324
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
2425
#include "tier4_autoware_utils/system/stop_watch.hpp"
@@ -136,11 +137,15 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
136137
rclcpp::Subscription<PredictedObjects>::SharedPtr objects_sub_;
137138
rclcpp::Subscription<Odometry>::SharedPtr odom_sub_;
138139
rclcpp::Subscription<AccelWithCovarianceStamped>::SharedPtr acc_sub_;
140+
rclcpp::Subscription<HADMapBin>::SharedPtr lanelet_map_sub_;
139141

140142
// data for callback functions
141143
PredictedObjects::ConstSharedPtr objects_ptr_{nullptr};
142144
Odometry::ConstSharedPtr ego_odom_ptr_{nullptr};
143145
AccelWithCovarianceStamped::ConstSharedPtr ego_accel_ptr_{nullptr};
146+
HADMapBin::ConstSharedPtr vector_map_ptr_{nullptr};
147+
148+
std::unique_ptr<route_handler::RouteHandler> route_handler_;
144149

145150
// Vehicle Parameters
146151
VehicleInfo vehicle_info_;
@@ -198,6 +203,9 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
198203
// consideration for the current ego pose
199204
bool enable_to_consider_current_pose{false};
200205
double time_to_convergence{1.5};
206+
bool work_as_pseudo_occlusion{false};
207+
double max_obj_vel_for_pseudo_occlusion{0.0};
208+
std::vector<lanelet::Id> focus_intersections_for_pseudo_occlusion{};
201209
};
202210
BehaviorDeterminationParam behavior_determination_param_;
203211

planning/obstacle_cruise_planner/include/obstacle_cruise_planner/type_alias.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919

2020
#include "autoware_adapi_v1_msgs/msg/planning_behavior.hpp"
2121
#include "autoware_adapi_v1_msgs/msg/velocity_factor_array.hpp"
22+
#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp"
2223
#include "autoware_auto_perception_msgs/msg/predicted_object.hpp"
2324
#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp"
2425
#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
@@ -38,6 +39,7 @@
3839
using autoware_adapi_v1_msgs::msg::PlanningBehavior;
3940
using autoware_adapi_v1_msgs::msg::VelocityFactor;
4041
using autoware_adapi_v1_msgs::msg::VelocityFactorArray;
42+
using autoware_auto_mapping_msgs::msg::HADMapBin;
4143
using autoware_auto_perception_msgs::msg::ObjectClassification;
4244
using autoware_auto_perception_msgs::msg::PredictedObject;
4345
using autoware_auto_perception_msgs::msg::PredictedObjects;

planning/obstacle_cruise_planner/launch/obstacle_cruise_planner.launch.xml

+1
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
<remap from="~/input/trajectory" to="$(var input_trajectory)"/>
2727
<remap from="~/input/odometry" to="$(var input_odometry)"/>
2828
<remap from="~/input/objects" to="$(var input_objects)"/>
29+
<remap from="~/input/vector_map" to="$(var input_map)"/>
2930

3031
<!-- output -->
3132
<remap from="~/output/trajectory" to="$(var output_trajectory)"/>

planning/obstacle_cruise_planner/src/node.cpp

+69-2
Original file line numberDiff line numberDiff line change
@@ -16,14 +16,24 @@
1616

1717
#include "motion_utils/resample/resample.hpp"
1818
#include "motion_utils/trajectory/tmp_conversion.hpp"
19+
#include "motion_utils/trajectory/trajectory.hpp"
1920
#include "object_recognition_utils/predicted_path_utils.hpp"
2021
#include "obstacle_cruise_planner/polygon_utils.hpp"
2122
#include "obstacle_cruise_planner/utils.hpp"
2223
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
2324
#include "tier4_autoware_utils/ros/marker_helper.hpp"
2425
#include "tier4_autoware_utils/ros/update_param.hpp"
2526

27+
#include <lanelet2_extension/utility/message_conversion.hpp>
28+
#include <lanelet2_extension/utility/query.hpp>
29+
#include <lanelet2_extension/utility/utilities.hpp>
30+
2631
#include <boost/format.hpp>
32+
#include <boost/geometry/algorithms/intersects.hpp>
33+
#include <boost/geometry/algorithms/within.hpp>
34+
35+
#include <lanelet2_core/geometry/LineString.h>
36+
#include <lanelet2_core/geometry/Polygon.h>
2737

2838
#include <algorithm>
2939
#include <chrono>
@@ -275,6 +285,14 @@ ObstacleCruisePlannerNode::BehaviorDeterminationParam::BehaviorDeterminationPara
275285
"behavior_determination.consider_current_pose.enable_to_consider_current_pose");
276286
time_to_convergence = node.declare_parameter<double>(
277287
"behavior_determination.consider_current_pose.time_to_convergence");
288+
work_as_pseudo_occlusion = node.declare_parameter<bool>(
289+
"behavior_determination.slow_down.pseudo_occlusion.enable_function");
290+
if (work_as_pseudo_occlusion) {
291+
max_obj_vel_for_pseudo_occlusion = node.declare_parameter<double>(
292+
"behavior_determination.slow_down.pseudo_occlusion.max_obj_vel");
293+
focus_intersections_for_pseudo_occlusion = node.declare_parameter<std::vector<lanelet::Id>>(
294+
"behavior_determination.slow_down.pseudo_occlusion.focus_intersections");
295+
}
278296
}
279297

280298
void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam(
@@ -335,6 +353,17 @@ void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam(
335353
tier4_autoware_utils::updateParam<double>(
336354
parameters, "behavior_determination.consider_current_pose.time_to_convergence",
337355
time_to_convergence);
356+
tier4_autoware_utils::updateParam<bool>(
357+
parameters, "behavior_determination.slow_down.pseudo_occlusion.enable_function",
358+
work_as_pseudo_occlusion);
359+
if (work_as_pseudo_occlusion) {
360+
tier4_autoware_utils::updateParam<double>(
361+
parameters, "behavior_determination.slow_down.pseudo_occlusion.max_obj_vel",
362+
max_obj_vel_for_pseudo_occlusion);
363+
tier4_autoware_utils::updateParam<std::vector<lanelet::Id>>(
364+
parameters, "behavior_determination.slow_down.pseudo_occlusion.focus_intersections",
365+
focus_intersections_for_pseudo_occlusion);
366+
}
338367
}
339368

340369
ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & node_options)
@@ -357,6 +386,9 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions &
357386
acc_sub_ = create_subscription<AccelWithCovarianceStamped>(
358387
"~/input/acceleration", rclcpp::QoS{1},
359388
[this](const AccelWithCovarianceStamped::ConstSharedPtr msg) { ego_accel_ptr_ = msg; });
389+
lanelet_map_sub_ = create_subscription<HADMapBin>(
390+
"~/input/vector_map", rclcpp::QoS(10).transient_local(),
391+
[this](const HADMapBin::ConstSharedPtr msg) { vector_map_ptr_ = msg; });
360392

361393
// publisher
362394
trajectory_pub_ = create_publisher<Trajectory>("~/output/trajectory", 1);
@@ -483,14 +515,18 @@ rcl_interfaces::msg::SetParametersResult ObstacleCruisePlannerNode::onParam(
483515

484516
void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr msg)
485517
{
518+
stop_watch_.tic(__func__);
486519
const auto traj_points = motion_utils::convertToTrajectoryPointArray(*msg);
487520

488521
// check if subscribed variables are ready
489-
if (traj_points.empty() || !ego_odom_ptr_ || !ego_accel_ptr_ || !objects_ptr_) {
522+
if (
523+
traj_points.empty() || !ego_odom_ptr_ || !ego_accel_ptr_ || !objects_ptr_ || !vector_map_ptr_) {
490524
return;
491525
}
526+
if (route_handler_ == nullptr) {
527+
route_handler_ = std::make_unique<route_handler::RouteHandler>(*vector_map_ptr_);
528+
}
492529

493-
stop_watch_.tic(__func__);
494530
*debug_data_ptr_ = DebugData();
495531

496532
const auto is_driving_forward = motion_utils::isDrivingForwardWithTwist(traj_points);
@@ -1130,6 +1166,37 @@ std::optional<SlowDownObstacle> ObstacleCruisePlannerNode::createSlowDownObstacl
11301166
return std::nullopt;
11311167
}
11321168

1169+
const auto is_occlusion_object = [&]() {
1170+
if (
1171+
std::hypot(obstacle.twist.linear.x, obstacle.twist.linear.y) >
1172+
behavior_determination_param_.max_obj_vel_for_pseudo_occlusion + 1e-6) {
1173+
return false;
1174+
}
1175+
1176+
if (motion_utils::calcLateralOffset(traj_points, obstacle.pose.position) > 0.0) {
1177+
return true;
1178+
}
1179+
1180+
for (const auto & id : behavior_determination_param_.focus_intersections_for_pseudo_occlusion) {
1181+
if (id == 0) {
1182+
continue;
1183+
}
1184+
const auto intersection_poly =
1185+
lanelet::utils::to2D(route_handler_->getLaneletMapPtr()->polygonLayer.get(id))
1186+
.basicPolygon();
1187+
if (
1188+
boost::geometry::within(obstacle_poly, intersection_poly) ||
1189+
boost::geometry::intersects(obstacle_poly, intersection_poly)) {
1190+
return true;
1191+
}
1192+
}
1193+
return false;
1194+
};
1195+
1196+
if (behavior_determination_param_.work_as_pseudo_occlusion && !is_occlusion_object()) {
1197+
return std::nullopt;
1198+
}
1199+
11331200
// calculate front collision point
11341201
double front_min_dist = std::numeric_limits<double>::max();
11351202
geometry_msgs::msg::Point front_collision_point;

0 commit comments

Comments
 (0)