Skip to content

Commit 9b63f71

Browse files
committed
Merge branch main into autoware_msg
Signed-off-by: liu cui <cynthia.liu@autocore.ai>
2 parents b2d74ba + 9544e9c commit 9b63f71

File tree

101 files changed

+4464
-1792
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

101 files changed

+4464
-1792
lines changed

.github/CODEOWNERS

+1-1
Original file line numberDiff line numberDiff line change
@@ -205,7 +205,7 @@ planning/sampling_based_planner/frenet_planner/** maxime.clement@tier4.jp
205205
planning/sampling_based_planner/path_sampler/** maxime.clement@tier4.jp
206206
planning/sampling_based_planner/sampler_common/** maxime.clement@tier4.jp
207207
planning/scenario_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
208-
planning/static_centerline_optimizer/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp
208+
planning/static_centerline_generator/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp
209209
planning/surround_obstacle_checker/** satoshi.ota@tier4.jp
210210
sensing/gnss_poser/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
211211
sensing/image_diagnostics/** dai.nguyen@tier4.jp

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

+2-1
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,8 @@ class InterProcessPollingSubscriber
3838
noexec_subscription_options.callback_group = noexec_callback_group;
3939

4040
subscriber_ = node->create_subscription<T>(
41-
topic_name, rclcpp::QoS{1}, [node](const typename T::ConstSharedPtr msg) { assert(false); },
41+
topic_name, rclcpp::QoS{1},
42+
[node]([[maybe_unused]] const typename T::ConstSharedPtr msg) { assert(false); },
4243
noexec_subscription_options);
4344
};
4445
bool updateLatestData()

launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -281,7 +281,7 @@ def create_single_frame_obstacle_segmentation_components(self, input_topic, outp
281281
use_additional = bool(additional_lidars)
282282
relay_topic = "all_lidars/pointcloud"
283283
common_pipeline_output = (
284-
"single_frame/pointcloud" if use_additional or use_ransac else output_topic
284+
"common/pointcloud" if use_additional or use_ransac else output_topic
285285
)
286286

287287
components = self.create_common_pipeline(

map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ def generate_test_description():
6161
LaunchDescription(
6262
[
6363
map_projection_loader_node,
64-
# Start test after 1s - gives time for the static_centerline_optimizer to finish initialization
64+
# Start test after 1s - gives time for the static_centerline_generator to finish initialization
6565
launch.actions.TimerAction(
6666
period=1.0, actions=[launch_testing.actions.ReadyToTest()]
6767
),

map/map_projection_loader/test/test_node_load_local_from_yaml.test.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ def generate_test_description():
6161
LaunchDescription(
6262
[
6363
map_projection_loader_node,
64-
# Start test after 1s - gives time for the static_centerline_optimizer to finish initialization
64+
# Start test after 1s - gives time for the static_centerline_generator to finish initialization
6565
launch.actions.TimerAction(
6666
period=1.0, actions=[launch_testing.actions.ReadyToTest()]
6767
),

map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ def generate_test_description():
6161
LaunchDescription(
6262
[
6363
map_projection_loader_node,
64-
# Start test after 1s - gives time for the static_centerline_optimizer to finish initialization
64+
# Start test after 1s - gives time for the static_centerline_generator to finish initialization
6565
launch.actions.TimerAction(
6666
period=1.0, actions=[launch_testing.actions.ReadyToTest()]
6767
),

map/map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ def generate_test_description():
6161
LaunchDescription(
6262
[
6363
map_projection_loader_node,
64-
# Start test after 1s - gives time for the static_centerline_optimizer to finish initialization
64+
# Start test after 1s - gives time for the static_centerline_generator to finish initialization
6565
launch.actions.TimerAction(
6666
period=1.0, actions=[launch_testing.actions.ReadyToTest()]
6767
),

perception/ground_segmentation/config/ground_segmentation.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -33,3 +33,4 @@
3333
center_pcl_shift: 0.0
3434
radial_divider_angle_deg: 1.0
3535
use_recheck_ground_cluster: true
36+
use_lowest_point: true

perception/ground_segmentation/config/scan_ground_filter.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -15,3 +15,4 @@
1515
center_pcl_shift: 0.0
1616
radial_divider_angle_deg: 1.0
1717
use_recheck_ground_cluster: true
18+
use_lowest_point: true

perception/ground_segmentation/docs/scan-ground-filter.md

+1
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,7 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref
5050
| `low_priority_region_x` | float | -20.0 | The non-zero x threshold in back side from which small objects detection is low priority [m] |
5151
| `elevation_grid_mode` | bool | true | Elevation grid scan mode option |
5252
| `use_recheck_ground_cluster` | bool | true | Enable recheck ground cluster |
53+
| `use_lowest_point` | bool | true | to select lowest point for reference in recheck ground cluster, otherwise select middle point |
5354

5455
## Assumptions / Known limits
5556

perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -194,6 +194,8 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter
194194
split_height_distance_; // useful for close points
195195
bool use_virtual_ground_point_;
196196
bool use_recheck_ground_cluster_; // to enable recheck ground cluster
197+
bool use_lowest_point_; // to select lowest point for reference in recheck ground cluster,
198+
// otherwise select middle point
197199
size_t radial_dividers_num_;
198200
VehicleInfo vehicle_info_;
199201

@@ -258,7 +260,7 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter
258260
* @param non_ground_indices Output non-ground PointCloud indices
259261
*/
260262
void recheckGroundCluster(
261-
PointsCentroid & gnd_cluster, const float non_ground_threshold,
263+
PointsCentroid & gnd_cluster, const float non_ground_threshold, const bool use_lowest_point,
262264
pcl::PointIndices & non_ground_indices);
263265
/*!
264266
* Returns the resulting complementary PointCloud, one with the points kept

perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp

+7-4
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,7 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions &
5757
split_height_distance_ = declare_parameter<float>("split_height_distance");
5858
use_virtual_ground_point_ = declare_parameter<bool>("use_virtual_ground_point");
5959
use_recheck_ground_cluster_ = declare_parameter<bool>("use_recheck_ground_cluster");
60+
use_lowest_point_ = declare_parameter<bool>("use_lowest_point");
6061
radial_dividers_num_ = std::ceil(2.0 * M_PI / radial_divider_angle_rad_);
6162
vehicle_info_ = VehicleInfoUtil(*this).getVehicleInfo();
6263

@@ -316,14 +317,15 @@ void ScanGroundFilterComponent::checkBreakGndGrid(
316317
}
317318

318319
void ScanGroundFilterComponent::recheckGroundCluster(
319-
PointsCentroid & gnd_cluster, const float non_ground_threshold,
320+
PointsCentroid & gnd_cluster, const float non_ground_threshold, const bool use_lowest_point,
320321
pcl::PointIndices & non_ground_indices)
321322
{
322-
const float min_gnd_height = gnd_cluster.getMinHeight();
323+
float reference_height =
324+
use_lowest_point ? gnd_cluster.getMinHeight() : gnd_cluster.getAverageHeight();
323325
const pcl::PointIndices & gnd_indices = gnd_cluster.getIndicesRef();
324326
const std::vector<float> & height_list = gnd_cluster.getHeightListRef();
325327
for (size_t i = 0; i < height_list.size(); ++i) {
326-
if (height_list.at(i) >= min_gnd_height + non_ground_threshold) {
328+
if (height_list.at(i) >= reference_height + non_ground_threshold) {
327329
non_ground_indices.indices.push_back(gnd_indices.indices.at(i));
328330
}
329331
}
@@ -403,7 +405,8 @@ void ScanGroundFilterComponent::classifyPointCloudGridScan(
403405
if (p->grid_id > prev_p->grid_id && ground_cluster.getAverageRadius() > 0.0) {
404406
// check if the prev grid have ground point cloud
405407
if (use_recheck_ground_cluster_) {
406-
recheckGroundCluster(ground_cluster, non_ground_height_threshold_, out_no_ground_indices);
408+
recheckGroundCluster(
409+
ground_cluster, non_ground_height_threshold_, use_lowest_point_, out_no_ground_indices);
407410
}
408411
curr_gnd_grid.radius = ground_cluster.getAverageRadius();
409412
curr_gnd_grid.avg_height = ground_cluster.getAverageHeight();

perception/ground_segmentation/test/test_scan_ground_filter.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -83,6 +83,7 @@ class ScanGroundFilterTest : public ::testing::Test
8383
rclcpp::Parameter("radial_divider_angle_deg", radial_divider_angle_deg_));
8484
parameters.emplace_back(
8585
rclcpp::Parameter("use_recheck_ground_cluster", use_recheck_ground_cluster_));
86+
parameters.emplace_back(rclcpp::Parameter("use_lowest_point", use_lowest_point_));
8687

8788
options.parameter_overrides(parameters);
8889

@@ -157,6 +158,7 @@ class ScanGroundFilterTest : public ::testing::Test
157158
center_pcl_shift_ = params["center_pcl_shift"].as<float>();
158159
radial_divider_angle_deg_ = params["radial_divider_angle_deg"].as<float>();
159160
use_recheck_ground_cluster_ = params["use_recheck_ground_cluster"].as<bool>();
161+
use_lowest_point_ = params["use_lowest_point"].as<bool>();
160162
}
161163

162164
float global_slope_max_angle_deg_ = 0.0;
@@ -174,6 +176,7 @@ class ScanGroundFilterTest : public ::testing::Test
174176
float center_pcl_shift_;
175177
float radial_divider_angle_deg_;
176178
bool use_recheck_ground_cluster_;
179+
bool use_lowest_point_;
177180
};
178181

179182
TEST_F(ScanGroundFilterTest, TestCase1)

perception/map_based_prediction/src/map_based_prediction_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -1367,15 +1367,15 @@ void MapBasedPredictionNode::removeOldObjectsHistory(
13671367
const double latest_object_time = rclcpp::Time(object_data.back().header.stamp).seconds();
13681368

13691369
// Delete Old Objects
1370-
if (current_time - latest_object_time > 2.0) {
1370+
if (current_time - latest_object_time > object_buffer_time_length_) {
13711371
invalid_object_id.push_back(object_id);
13721372
continue;
13731373
}
13741374

13751375
// Delete old information
13761376
while (!object_data.empty()) {
13771377
const double post_object_time = rclcpp::Time(object_data.front().header.stamp).seconds();
1378-
if (current_time - post_object_time > 2.0) {
1378+
if (current_time - post_object_time > object_buffer_time_length_) {
13791379
// Delete Old Position
13801380
object_data.pop_front();
13811381
} else {

perception/multi_object_tracker/CMakeLists.txt

+7-4
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@ include_directories(
2323
set(MULTI_OBJECT_TRACKER_SRC
2424
src/multi_object_tracker_core.cpp
2525
src/debugger.cpp
26+
src/processor/processor.cpp
2627
src/data_association/data_association.cpp
2728
src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp
2829
src/tracker/motion_model/motion_model_base.cpp
@@ -47,12 +48,14 @@ ament_auto_add_library(multi_object_tracker_node SHARED
4748

4849
target_link_libraries(multi_object_tracker_node
4950
Eigen3::Eigen
50-
glog::glog
5151
)
5252

53-
rclcpp_components_register_node(multi_object_tracker_node
54-
PLUGIN "MultiObjectTracker"
55-
EXECUTABLE multi_object_tracker
53+
ament_auto_add_executable(${PROJECT_NAME}
54+
src/multi_object_tracker_node.cpp
55+
)
56+
57+
target_link_libraries(${PROJECT_NAME}
58+
multi_object_tracker_node glog
5659
)
5760

5861
ament_auto_package(INSTALL_TO_SHARE

perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp

+7
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,10 @@ class TrackerDebugger
4141
const autoware_perception_msgs::msg::TrackedObjects & tentative_objects) const;
4242
void startMeasurementTime(
4343
const rclcpp::Time & now, const rclcpp::Time & measurement_header_stamp);
44+
void endMeasurementTime(const rclcpp::Time & now);
45+
void startPublishTime(const rclcpp::Time & now);
4446
void endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time);
47+
4548
void setupDiagnostics();
4649
void checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat);
4750
struct DEBUG_SETTINGS
@@ -53,15 +56,19 @@ class TrackerDebugger
5356
} debug_settings_;
5457
double pipeline_latency_ms_ = 0.0;
5558
diagnostic_updater::Updater diagnostic_updater_;
59+
bool shouldPublishTentativeObjects() const { return debug_settings_.publish_tentative_objects; }
5660

5761
private:
5862
void loadParameters();
63+
bool is_initialized_ = false;
5964
rclcpp::Node & node_;
6065
rclcpp::Publisher<autoware_perception_msgs::msg::TrackedObjects>::SharedPtr
6166
debug_tentative_objects_pub_;
6267
std::unique_ptr<tier4_autoware_utils::DebugPublisher> processing_time_publisher_;
6368
rclcpp::Time last_input_stamp_;
6469
rclcpp::Time stamp_process_start_;
70+
rclcpp::Time stamp_process_end_;
71+
rclcpp::Time stamp_publish_start_;
6572
rclcpp::Time stamp_publish_output_;
6673
};
6774

perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp

+17-19
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121

2222
#include "multi_object_tracker/data_association/data_association.hpp"
2323
#include "multi_object_tracker/debugger.hpp"
24+
#include "multi_object_tracker/processor/processor.hpp"
2425
#include "multi_object_tracker/tracker/model/tracker_base.hpp"
2526

2627
#include <rclcpp/rclcpp.hpp>
@@ -46,6 +47,7 @@
4647
#include <map>
4748
#include <memory>
4849
#include <string>
50+
#include <unordered_map>
4951
#include <vector>
5052

5153
class MultiObjectTracker : public rclcpp::Node
@@ -54,39 +56,35 @@ class MultiObjectTracker : public rclcpp::Node
5456
explicit MultiObjectTracker(const rclcpp::NodeOptions & node_options);
5557

5658
private:
59+
// ROS interface
5760
rclcpp::Publisher<autoware_perception_msgs::msg::TrackedObjects>::SharedPtr
5861
tracked_objects_pub_;
5962
rclcpp::Subscription<autoware_perception_msgs::msg::DetectedObjects>::SharedPtr
6063
detected_object_sub_;
61-
rclcpp::TimerBase::SharedPtr publish_timer_; // publish timer
62-
63-
// debugger class
64-
std::unique_ptr<TrackerDebugger> debugger_;
65-
6664
tf2_ros::Buffer tf_buffer_;
6765
tf2_ros::TransformListener tf_listener_;
6866

69-
std::map<std::uint8_t, std::string> tracker_map_;
70-
67+
// debugger
68+
std::unique_ptr<TrackerDebugger> debugger_;
7169
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
7270

73-
void onMeasurement(
74-
const autoware_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg);
75-
void onTimer();
71+
// publish timer
72+
rclcpp::TimerBase::SharedPtr publish_timer_;
73+
rclcpp::Time last_published_time_;
74+
double publisher_period_;
7675

76+
// internal states
7777
std::string world_frame_id_; // tracking frame
78-
std::list<std::shared_ptr<Tracker>> list_tracker_;
7978
std::unique_ptr<DataAssociation> data_association_;
79+
std::unique_ptr<TrackerProcessor> processor_;
8080

81-
void checkTrackerLifeCycle(
82-
std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time,
83-
const geometry_msgs::msg::Transform & self_transform);
84-
void sanitizeTracker(
85-
std::list<std::shared_ptr<Tracker>> & list_tracker, const rclcpp::Time & time);
86-
std::shared_ptr<Tracker> createNewTracker(
87-
const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
88-
const geometry_msgs::msg::Transform & self_transform) const;
81+
// callback functions
82+
void onMeasurement(
83+
const autoware_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg);
84+
void onTimer();
8985

86+
// publish processes
87+
void checkAndPublish(const rclcpp::Time & time);
9088
void publish(const rclcpp::Time & time) const;
9189
inline bool shouldTrackerPublish(const std::shared_ptr<const Tracker> tracker) const;
9290
};
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,79 @@
1+
// Copyright 2024 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
//
15+
//
16+
17+
#ifndef MULTI_OBJECT_TRACKER__PROCESSOR__PROCESSOR_HPP_
18+
#define MULTI_OBJECT_TRACKER__PROCESSOR__PROCESSOR_HPP_
19+
20+
#include "multi_object_tracker/tracker/model/tracker_base.hpp"
21+
22+
#include <rclcpp/rclcpp.hpp>
23+
24+
#include <autoware_perception_msgs/msg/detected_objects.hpp>
25+
#include <autoware_perception_msgs/msg/tracked_objects.hpp>
26+
27+
#include <list>
28+
#include <map>
29+
#include <memory>
30+
#include <string>
31+
#include <unordered_map>
32+
#include <vector>
33+
34+
class TrackerProcessor
35+
{
36+
public:
37+
explicit TrackerProcessor(const std::map<std::uint8_t, std::string> & tracker_map);
38+
39+
const std::list<std::shared_ptr<Tracker>> & getListTracker() const { return list_tracker_; }
40+
// tracker processes
41+
void predict(const rclcpp::Time & time);
42+
void update(
43+
const autoware_perception_msgs::msg::DetectedObjects & transformed_objects,
44+
const geometry_msgs::msg::Transform & self_transform,
45+
const std::unordered_map<int, int> & direct_assignment);
46+
void spawn(
47+
const autoware_perception_msgs::msg::DetectedObjects & detected_objects,
48+
const geometry_msgs::msg::Transform & self_transform,
49+
const std::unordered_map<int, int> & reverse_assignment);
50+
void prune(const rclcpp::Time & time);
51+
52+
// output
53+
bool isConfidentTracker(const std::shared_ptr<Tracker> & tracker) const;
54+
void getTrackedObjects(
55+
const rclcpp::Time & time,
56+
autoware_perception_msgs::msg::TrackedObjects & tracked_objects) const;
57+
void getTentativeObjects(
58+
const rclcpp::Time & time,
59+
autoware_perception_msgs::msg::TrackedObjects & tentative_objects) const;
60+
61+
private:
62+
std::map<std::uint8_t, std::string> tracker_map_;
63+
std::list<std::shared_ptr<Tracker>> list_tracker_;
64+
65+
// parameters
66+
float max_elapsed_time_; // [s]
67+
float min_iou_; // [ratio]
68+
float min_iou_for_unknown_object_; // [ratio]
69+
double distance_threshold_; // [m]
70+
int confident_count_threshold_; // [count]
71+
72+
void removeOldTracker(const rclcpp::Time & time);
73+
void removeOverlappedTracker(const rclcpp::Time & time);
74+
std::shared_ptr<Tracker> createNewTracker(
75+
const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
76+
const geometry_msgs::msg::Transform & self_transform) const;
77+
};
78+
79+
#endif // MULTI_OBJECT_TRACKER__PROCESSOR__PROCESSOR_HPP_

perception/multi_object_tracker/package.xml

-1
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,6 @@
2525
<depend>tf2</depend>
2626
<depend>tf2_ros</depend>
2727
<depend>tier4_autoware_utils</depend>
28-
<depend>tier4_perception_msgs</depend>
2928
<depend>unique_identifier_msgs</depend>
3029

3130
<test_depend>ament_lint_auto</test_depend>

0 commit comments

Comments
 (0)