Skip to content

Commit 7956221

Browse files
authored
Merge branch 'beta/x2_gen2/v0.29.0' into cherry-pick/aeb-latest-to-v4.0.0
2 parents 32808d4 + 2b55cc9 commit 7956221

File tree

33 files changed

+754
-219
lines changed

33 files changed

+754
-219
lines changed

control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -556,14 +556,14 @@ void VehicleCmdGate::publishControlCommands(const Commands & commands)
556556

557557
// Check engage
558558
if (!is_engaged_) {
559-
filtered_commands.control.longitudinal = createLongitudinalStopControlCmd();
559+
filtered_commands.control = createStopControlCmd();
560560
}
561561

562562
// Check pause. Place this check after all other checks as it needs the final output.
563563
adapi_pause_->update(filtered_commands.control);
564564
if (adapi_pause_->is_paused()) {
565565
if (is_engaged_) {
566-
filtered_commands.control.longitudinal = createLongitudinalStopControlCmd();
566+
filtered_commands.control = createStopControlCmd();
567567
} else {
568568
filtered_commands.control = createStopControlCmd();
569569
}

launch/tier4_system_launch/launch/system.launch.xml

+6
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222

2323
<arg name="launch_system_monitor" default="true" description="launch system monitor"/>
2424
<arg name="launch_dummy_diag_publisher" description="launch dummy diag publisher"/>
25+
<arg name="launch_system_recover_operator" default="false" description="launch recover operator"/>
2526
<arg name="run_mode" default="online" description="options: online, logging_simulation, planning_simulation"/>
2627
<arg name="sensor_model" description="sensor model name"/>
2728

@@ -142,4 +143,9 @@
142143
<arg name="launch_rqt_runtime_monitor_err" value="$(var launch_rqt_runtime_monitor_err)"/>
143144
</include>
144145
</group>
146+
147+
<!-- System Recover Operator -->
148+
<group if="$(var launch_system_recover_operator)">
149+
<node pkg="diagnostic_graph_utils" exec="recovery_node" name="recovery"/>
150+
</group>
145151
</launch>

perception/image_projection_based_fusion/src/fusion_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -54,8 +54,8 @@ FusionNode<TargetMsg3D, ObjType, Msg2D>::FusionNode(
5454
}
5555
if (rois_number_ > 8) {
5656
RCLCPP_WARN(
57-
this->get_logger(), "maximum rois_number is 8. current rois_number is %zu", rois_number_);
58-
rois_number_ = 8;
57+
this->get_logger(),
58+
"Current rois_number is %zu. Large rois number may cause performance issue.", rois_number_);
5959
}
6060

6161
// Set parameters

perception/lidar_centerpoint/include/lidar_centerpoint/postprocess/non_maximum_suppression.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -66,14 +66,14 @@ class NonMaximumSuppression
6666
std::vector<DetectedObject> apply(const std::vector<DetectedObject> &);
6767

6868
private:
69-
bool isTargetLabel(const std::uint8_t);
70-
7169
bool isTargetPairObject(const DetectedObject &, const DetectedObject &);
7270

7371
Eigen::MatrixXd generateIoUMatrix(const std::vector<DetectedObject> &);
7472

7573
NMSParams params_{};
7674
std::vector<bool> target_class_mask_{};
75+
76+
double search_distance_2d_sq_{};
7777
};
7878

7979
} // namespace centerpoint

perception/lidar_centerpoint/lib/centerpoint_trt.cpp

+15-2
Original file line numberDiff line numberDiff line change
@@ -115,15 +115,28 @@ bool CenterPointTRT::detect(
115115
cudaMemsetAsync(spatial_features_d_.get(), 0, spatial_features_size_ * sizeof(float), stream_));
116116

117117
if (!preprocess(input_pointcloud_msg, tf_buffer)) {
118-
RCLCPP_WARN_STREAM(
119-
rclcpp::get_logger("lidar_centerpoint"), "Fail to preprocess and skip to detect.");
118+
RCLCPP_WARN(rclcpp::get_logger("lidar_centerpoint"), "Fail to preprocess and skip to detect.");
120119
return false;
121120
}
122121

123122
inference();
124123

125124
postProcess(det_boxes3d);
126125

126+
// Check the actual number of pillars after inference to avoid unnecessary synchronization.
127+
unsigned int num_pillars = 0;
128+
CHECK_CUDA_ERROR(
129+
cudaMemcpy(&num_pillars, num_voxels_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost));
130+
131+
if (num_pillars >= config_.max_voxel_size_) {
132+
rclcpp::Clock clock{RCL_ROS_TIME};
133+
RCLCPP_WARN_THROTTLE(
134+
rclcpp::get_logger("lidar_centerpoint"), clock, 1000,
135+
"The actual number of pillars (%u) exceeds its maximum value (%zu). "
136+
"Please considering increasing it since it may limit the detection performance.",
137+
num_pillars, config_.max_voxel_size_);
138+
}
139+
127140
return true;
128141
}
129142

perception/lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp

+6-12
Original file line numberDiff line numberDiff line change
@@ -19,38 +19,32 @@
1919
#include "object_recognition_utils/object_recognition_utils.hpp"
2020
namespace centerpoint
2121
{
22+
using Label = autoware_perception_msgs::msg::ObjectClassification;
2223

2324
void NonMaximumSuppression::setParameters(const NMSParams & params)
2425
{
2526
assert(params.search_distance_2d_ >= 0.0);
2627
assert(params.iou_threshold_ >= 0.0 && params.iou_threshold_ <= 1.0);
2728

2829
params_ = params;
30+
search_distance_2d_sq_ = params.search_distance_2d_ * params.search_distance_2d_;
2931
target_class_mask_ = classNamesToBooleanMask(params.target_class_names_);
3032
}
3133

32-
bool NonMaximumSuppression::isTargetLabel(const uint8_t label)
33-
{
34-
if (label >= target_class_mask_.size()) {
35-
return false;
36-
}
37-
return target_class_mask_.at(label);
38-
}
39-
4034
bool NonMaximumSuppression::isTargetPairObject(
4135
const DetectedObject & object1, const DetectedObject & object2)
4236
{
4337
const auto label1 = object_recognition_utils::getHighestProbLabel(object1.classification);
4438
const auto label2 = object_recognition_utils::getHighestProbLabel(object2.classification);
4539

46-
if (isTargetLabel(label1) && isTargetLabel(label2)) {
47-
return true;
40+
// if labels are not the same, and one of them is pedestrian, do not suppress
41+
if (label1 != label2 && (label1 == Label::PEDESTRIAN || label2 == Label::PEDESTRIAN)) {
42+
return false;
4843
}
4944

50-
const auto search_sqr_dist_2d = params_.search_distance_2d_ * params_.search_distance_2d_;
5145
const auto sqr_dist_2d = autoware::universe_utils::calcSquaredDistance2d(
5246
object_recognition_utils::getPose(object1), object_recognition_utils::getPose(object2));
53-
return sqr_dist_2d <= search_sqr_dist_2d;
47+
return sqr_dist_2d <= search_distance_2d_sq_;
5448
}
5549

5650
Eigen::MatrixXd NonMaximumSuppression::generateIoUMatrix(

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,7 @@ If the target path contains a goal, modify the points of the path so that the pa
107107
- Route is set with `allow_goal_modification=true` .
108108
- We can set this option with [SetRoute](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/routing/srv/SetRoute.srv#L2) api service.
109109
- We support `2D Rough Goal Pose` with the key bind `r` in RViz, but in the future there will be a panel of tools to manipulate various Route API from RViz.
110-
- ego-vehicle is in the same lane as the goal.
110+
- The terminal point of the current path is in the same lane sequence as the goal. If goal is on the road shoulder, then it is in the adjacent road lane sequence.
111111

112112
<img src="https://user-images.githubusercontent.com/39142679/237929950-989ca6c3-d48c-4bb5-81e5-e8d6a38911aa.png" width="600">
113113

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -266,6 +266,7 @@ struct GoalPlannerDebugData
266266
FreespacePlannerDebugData freespace_planner{};
267267
std::vector<Polygon2d> ego_polygons_expanded{};
268268
lanelet::ConstLanelet expanded_pull_over_lane_between_ego{};
269+
Polygon2d objects_extraction_polygon{};
269270
};
270271

271272
struct LastApprovalData

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -31,13 +31,12 @@ class GoalSearcher : public GoalSearcherBase
3131
public:
3232
GoalSearcher(const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint);
3333

34-
GoalCandidates search(
35-
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
36-
const std::shared_ptr<const PlannerData> & planner_data) override;
34+
GoalCandidates search(const std::shared_ptr<const PlannerData> & planner_data) override;
3735
void update(
3836
GoalCandidates & goal_candidates,
3937
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
40-
const std::shared_ptr<const PlannerData> & planner_data) const override;
38+
const std::shared_ptr<const PlannerData> & planner_data,
39+
const PredictedObjects & objects) const override;
4140

4241
// todo(kosuke55): Functions for this specific use should not be in the interface,
4342
// so it is better to consider interface design when we implement other goal searchers.
@@ -47,7 +46,8 @@ class GoalSearcher : public GoalSearcherBase
4746
bool isSafeGoalWithMarginScaleFactor(
4847
const GoalCandidate & goal_candidate, const double margin_scale_factor,
4948
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
50-
const std::shared_ptr<const PlannerData> & planner_data) const override;
49+
const std::shared_ptr<const PlannerData> & planner_data,
50+
const PredictedObjects & objects) const override;
5151

5252
private:
5353
void countObjectsToAvoid(

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -53,13 +53,12 @@ class GoalSearcherBase
5353
const Pose & getReferenceGoal() const { return reference_goal_pose_; }
5454

5555
MultiPolygon2d getAreaPolygons() const { return area_polygons_; }
56-
virtual GoalCandidates search(
57-
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
58-
const std::shared_ptr<const PlannerData> & planner_data) = 0;
56+
virtual GoalCandidates search(const std::shared_ptr<const PlannerData> & planner_data) = 0;
5957
virtual void update(
6058
[[maybe_unused]] GoalCandidates & goal_candidates,
6159
[[maybe_unused]] const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
62-
[[maybe_unused]] const std::shared_ptr<const PlannerData> & planner_data) const
60+
[[maybe_unused]] const std::shared_ptr<const PlannerData> & planner_data,
61+
[[maybe_unused]] const PredictedObjects & objects) const
6362
{
6463
return;
6564
}
@@ -69,7 +68,8 @@ class GoalSearcherBase
6968
virtual bool isSafeGoalWithMarginScaleFactor(
7069
const GoalCandidate & goal_candidate, const double margin_scale_factor,
7170
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
72-
const std::shared_ptr<const PlannerData> & planner_data) const = 0;
71+
const std::shared_ptr<const PlannerData> & planner_data,
72+
const PredictedObjects & objects) const = 0;
7373

7474
protected:
7575
GoalPlannerParameters parameters_{};

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/shift_pull_over.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ class ShiftPullOver : public PullOverPlannerBase
4343
std::optional<PathWithLaneId> cropPrevModulePath(
4444
const PathWithLaneId & prev_module_path, const Pose & shift_end_pose) const;
4545
std::optional<PullOverPath> generatePullOverPath(
46-
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
46+
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes,
4747
const Pose & goal_pose, const double lateral_jerk) const;
4848
static double calcBeforeShiftedArcLength(
4949
const PathWithLaneId & path, const double after_shifted_arc_length, const double dr);

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp

+53-4
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,19 @@ lanelet::ConstLanelets generateBetweenEgoAndExpandedPullOverLanes(
6262
const geometry_msgs::msg::Pose ego_pose,
6363
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double outer_road_offset,
6464
const double inner_road_offset);
65+
66+
/*
67+
* @brief generate polygon to extract objects
68+
* @param pull_over_lanes pull over lanes
69+
* @param left_side left side or right side
70+
* @param outer_offset outer offset from pull over lane boundary
71+
* @param inner_offset inner offset from pull over lane boundary
72+
* @return polygon to extract objects
73+
*/
74+
std::optional<Polygon2d> generateObjectExtractionPolygon(
75+
const lanelet::ConstLanelets & pull_over_lanes, const bool left_side, const double outer_offset,
76+
const double inner_offset);
77+
6578
PredictedObjects extractObjectsInExpandedPullOverLanes(
6679
const RouteHandler & route_handler, const bool left_side, const double backward_distance,
6780
const double forward_distance, double bound_offset, const PredictedObjects & objects);
@@ -82,12 +95,31 @@ bool isReferencePath(
8295
std::optional<PathWithLaneId> cropPath(const PathWithLaneId & path, const Pose & end_pose);
8396
PathWithLaneId cropForwardPoints(
8497
const PathWithLaneId & path, const size_t target_seg_idx, const double forward_length);
98+
99+
/**
100+
* @brief extend target_path by extend_length
101+
* @param target_path original target path to extend
102+
* @param reference_path reference path to extend
103+
* @param extend_length length to extend
104+
* @param remove_connected_zero_velocity flag to remove zero velocity if the last point of
105+
* target_path has zero velocity
106+
* @return extended path
107+
*/
85108
PathWithLaneId extendPath(
86-
const PathWithLaneId & prev_module_path, const PathWithLaneId & reference_path,
87-
const double extend_length);
109+
const PathWithLaneId & target_path, const PathWithLaneId & reference_path,
110+
const double extend_length, const bool remove_connected_zero_velocity);
111+
/**
112+
* @brief extend target_path to extend_pose
113+
* @param target_path original target path to extend
114+
* @param reference_path reference path to extend
115+
* @param extend_pose pose to extend
116+
* @param remove_connected_zero_velocity flag to remove zero velocity if the last point of
117+
* target_path has zero velocity
118+
* @return extended path
119+
*/
88120
PathWithLaneId extendPath(
89-
const PathWithLaneId & prev_module_path, const PathWithLaneId & reference_path,
90-
const Pose & extend_pose);
121+
const PathWithLaneId & target_path, const PathWithLaneId & reference_path,
122+
const Pose & extend_pose, const bool remove_connected_zero_velocity);
91123

92124
std::vector<Polygon2d> createPathFootPrints(
93125
const PathWithLaneId & path, const double base_to_front, const double base_to_rear,
@@ -109,6 +141,23 @@ MarkerArray createLaneletPolygonMarkerArray(
109141
MarkerArray createNumObjectsToAvoidTextsMarkerArray(
110142
const GoalCandidates & goal_candidates, std::string && ns,
111143
const std_msgs::msg::ColorRGBA & color);
144+
145+
/**
146+
* @brief combine two points
147+
* @param points lane points
148+
* @param points_next next lane points
149+
* @return combined points
150+
*/
151+
lanelet::Points3d combineLanePoints(
152+
const lanelet::Points3d & points, const lanelet::Points3d & points_next);
153+
/** @brief Create a lanelet that represents the departure check area.
154+
* @param [in] pull_over_lanes Lanelets that the vehicle will pull over to.
155+
* @param [in] route_handler RouteHandler object.
156+
* @return Lanelet that goal footprints should be inside.
157+
*/
158+
lanelet::Lanelet createDepartureCheckLanelet(
159+
const lanelet::ConstLanelets & pull_over_lanes, const route_handler::RouteHandler & route_handler,
160+
const bool left_side_parking);
112161
} // namespace autoware::behavior_path_planner::goal_planner_utils
113162

114163
#endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/geometric_pull_over.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,6 @@ std::optional<PullOverPath> GeometricPullOver::plan(const Pose & goal_pose)
5151
if (road_lanes.empty() || pull_over_lanes.empty()) {
5252
return {};
5353
}
54-
const auto lanes = utils::combineLanelets(road_lanes, pull_over_lanes);
5554

5655
const auto & p = parallel_parking_parameters_;
5756
const double max_steer_angle =
@@ -65,10 +64,12 @@ std::optional<PullOverPath> GeometricPullOver::plan(const Pose & goal_pose)
6564
return {};
6665
}
6766

67+
const auto departure_check_lane = goal_planner_utils::createDepartureCheckLanelet(
68+
pull_over_lanes, *planner_data_->route_handler, left_side_parking_);
6869
const auto arc_path = planner_.getArcPath();
6970

7071
// check lane departure with road and shoulder lanes
71-
if (lane_departure_checker_.checkPathWillLeaveLane(lanes, arc_path)) return {};
72+
if (lane_departure_checker_.checkPathWillLeaveLane({departure_check_lane}, arc_path)) return {};
7273

7374
PullOverPath pull_over_path{};
7475
pull_over_path.type = getPlannerType();

0 commit comments

Comments
 (0)