Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(multi_object_tracker): put node parameters to yaml file #5769

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
<?xml version="1.0"?>
<launch>
<arg name="mode" default="lidar" description="options: `camera_lidar_radar_fusion`, `camera_lidar_fusion`, `lidar_radar_fusion`, `lidar` or `radar`"/>
<arg name="publish_rate" default="10.0"/>
<arg name="enable_delay_compensation" default="true"/>

<!-- Radar Tracking and Merger parameters -->
<arg name="use_radar_tracking_fusion" default="false" description="use radar tracking fusion"/>
Expand All @@ -19,8 +17,7 @@
<!--multi object tracking-->
<include file="$(find-pkg-share multi_object_tracker)/launch/multi_object_tracker.launch.xml">
<arg name="data_association_matrix_path" value="$(var object_recognition_tracking_multi_object_tracker_data_association_matrix_param_path)"/>
<arg name="publish_rate" value="$(var publish_rate)"/>
<arg name="enable_delay_compensation" value="$(var enable_delay_compensation)"/>
<arg name="tracker_setting_path" value="$(var object_recognition_tracking_multi_object_tracker_node_param_path)"/>
</include>
</group>

Expand All @@ -29,15 +26,12 @@
<!--multi object tracking for near objects-->
<include file="$(find-pkg-share multi_object_tracker)/launch/multi_object_tracker.launch.xml">
<arg name="data_association_matrix_path" value="$(var object_recognition_tracking_multi_object_tracker_data_association_matrix_param_path)"/>
<arg name="publish_rate" value="$(var publish_rate)"/>
<arg name="enable_delay_compensation" value="$(var enable_delay_compensation)"/>
<arg name="tracker_setting_path" value="$(var object_recognition_tracking_multi_object_tracker_node_param_path)"/>
<arg name="output" value="/perception/object_recognition/tracking/near_objects"/>
</include>

<!--radar long range dynamic object tracking-->
<include file="$(find-pkg-share radar_object_tracker)/launch/radar_object_tracker.launch.xml">
<arg name="publish_rate" value="$(var publish_rate)"/>
<arg name="enable_delay_compensation" value="$(var enable_delay_compensation)"/>
<arg name="input" value="$(var radar_tracker_input)"/>
<arg name="output" value="$(var radar_tracker_output)"/>
<arg name="data_association_matrix_path" value="$(var object_recognition_tracking_radar_object_tracker_data_association_matrix_param_path)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
<arg name="object_recognition_detection_radar_lanelet_filtering_range_param"/>
<arg name="object_recognition_detection_radar_object_clustering_param_path"/>
<arg name="object_recognition_tracking_multi_object_tracker_data_association_matrix_param_path"/>
<arg name="object_recognition_tracking_multi_object_tracker_node_param_path"/>
<arg name="object_recognition_tracking_radar_object_tracker_data_association_matrix_param_path"/>
<arg name="object_recognition_tracking_radar_object_tracker_tracking_setting_param_path"/>
<arg name="obstacle_segmentation_ground_segmentation_param_path"/>
Expand Down
30 changes: 20 additions & 10 deletions perception/multi_object_tracker/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -70,16 +70,26 @@ Example:

### Core Parameters

| Name | Type | Description |
| --------------------------- | ------ | -------------------------------------------------------------- |
| `can_assign_matrix` | double | Assignment table for data association |
| `max_dist_matrix` | double | Maximum distance table for data association |
| `max_area_matrix` | double | Maximum area table for data association |
| `min_area_matrix` | double | Minimum area table for data association |
| `max_rad_matrix` | double | Maximum angle table for data association |
| `world_frame_id` | double | tracking frame |
| `enable_delay_compensation` | bool | Estimate obstacles at current time considering detection delay |
| `publish_rate` | double | if enable_delay_compensation is true, how many hertz to output |
Node parameters are defined in [multi_object_tracker.param.yaml](config/multi_object_tracker.param.yaml) and association parameters are defined in [data_association.param.yaml](config/data_association.param.yaml).

#### Node parameters

| Name | Type | Description |
| --------------------------- | ------ | --------------------------------------------------------------------------------------------------------------------------- |
| `***_tracker` | string | EKF tracker name for each class |
| `world_frame_id` | double | object kinematics definition frame |
| `enable_delay_compensation` | bool | if True, tracker use timers to schedule publishers and use prediction step to extrapolate object state at desired timestamp |
| `publish_rate` | double | Timer frequency to output with delay compensation |

#### Association parameters

| Name | Type | Description |
| ------------------- | ------ | ------------------------------------------- |
| `can_assign_matrix` | double | Assignment table for data association |
| `max_dist_matrix` | double | Maximum distance table for data association |
| `max_area_matrix` | double | Maximum area table for data association |
| `min_area_matrix` | double | Minimum area table for data association |
| `max_rad_matrix` | double | Maximum angle table for data association |

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,15 @@
/**:
ros__parameters:
# default tracker models for each class
car_tracker: "multi_vehicle_tracker"
truck_tracker: "multi_vehicle_tracker"
bus_tracker: "multi_vehicle_tracker"
trailer_tracker: "multi_vehicle_tracker"
pedestrian_tracker: "pedestrian_and_bicycle_tracker"
bicycle_tracker: "pedestrian_and_bicycle_tracker"
motorcycle_tracker: "pedestrian_and_bicycle_tracker"

# default tracker node parameters
publish_rate: 10.0
world_frame_id: map
enable_delay_compensation: false
Original file line number Diff line number Diff line change
Expand Up @@ -2,18 +2,12 @@
<launch>
<arg name="input" default="/perception/object_recognition/detection/objects"/>
<arg name="output" default="objects"/>
<arg name="world_frame_id" default="map"/>
<arg name="publish_rate" default="10.0"/>
<arg name="enable_delay_compensation" default="false"/>
<arg name="tracker_setting_path" default="$(find-pkg-share multi_object_tracker)/config/default_tracker.param.yaml"/>
<arg name="tracker_setting_path" default="$(find-pkg-share multi_object_tracker)/config/multi_object_tracker_node.param.yaml"/>
<arg name="data_association_matrix_path" default="$(find-pkg-share multi_object_tracker)/config/data_association_matrix.param.yaml"/>

<node pkg="multi_object_tracker" exec="multi_object_tracker" name="multi_object_tracker" output="screen">
<remap from="input" to="$(var input)"/>
<remap from="output" to="$(var output)"/>
<param name="world_frame_id" value="$(var world_frame_id)"/>
<param name="publish_rate" value="$(var publish_rate)"/>
<param name="enable_delay_compensation" value="$(var enable_delay_compensation)"/>
<param from="$(var tracker_setting_path)"/>
<param from="$(var data_association_matrix_path)"/>
</node>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,9 +78,9 @@
create_publisher<autoware_auto_perception_msgs::msg::TrackedObjects>("output", rclcpp::QoS{1});

// Parameters
double publish_rate = declare_parameter<double>("publish_rate", 30.0);
world_frame_id_ = declare_parameter<std::string>("world_frame_id", "world");
bool enable_delay_compensation{declare_parameter("enable_delay_compensation", false)};
double publish_rate = declare_parameter<double>("publish_rate");
world_frame_id_ = declare_parameter<std::string>("world_frame_id");
bool enable_delay_compensation{declare_parameter<bool>("enable_delay_compensation")};

Check warning on line 83 in perception/multi_object_tracker/src/multi_object_tracker_core.cpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/src/multi_object_tracker_core.cpp#L81-L83

Added lines #L81 - L83 were not covered by tests

auto cti = std::make_shared<tf2_ros::CreateTimerROS>(
this->get_node_base_interface(), this->get_node_timers_interface());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,6 @@
<launch>
<arg name="input" default="/perception/object_recognition/detection/objects"/>
<arg name="output" default="objects"/>
<arg name="world_frame_id" default="map"/>
<arg name="publish_rate" default="10.0"/>
<arg name="enable_delay_compensation" default="true"/>
<arg name="tracker_setting_path" default="$(find-pkg-share radar_object_tracker)/config/default_tracker.param.yaml"/>
<arg name="tracking_config_directory" default="$(find-pkg-share radar_object_tracker)/config/tracking/"/>
<arg name="data_association_matrix_path" default="$(find-pkg-share radar_object_tracker)/config/data_association_matrix.param.yaml"/>
Expand All @@ -19,8 +16,5 @@
<param from="$(var data_association_matrix_path)"/>
<param from="$(var radar_object_tracker_param_path)"/>
<param name="tracking_config_directory" value="$(var tracking_config_directory)"/>
<param name="world_frame_id" value="$(var world_frame_id)"/>
<param name="publish_rate" value="$(var publish_rate)"/>
<param name="enable_delay_compensation" value="$(var enable_delay_compensation)"/>
</node>
</launch>
Loading