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

feat(lidar_apollo_instance_segmentation): add build_only option #6454

Merged
merged 1 commit into from
Feb 20, 2024
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
1 change: 1 addition & 0 deletions perception/lidar_apollo_instance_segmentation/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ None
| `use_constant_feature` | bool | false | The flag to use direction and distance feature of pointcloud. |
| `target_frame` | string | "base_link" | Pointcloud data is transformed into this frame. |
| `z_offset` | int | 2 | z offset from target frame. [m] |
| `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built |

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
<arg name="input/pointcloud" default="/sensing/lidar/pointcloud"/>
<arg name="model" default="model_128"/>
<arg name="output/objects" default="labeled_clusters"/>
<arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>

<arg if="$(eval &quot;'$(var model)'=='model_16'&quot;)" name="base_name" default="vlp-16"/>
<arg if="$(eval &quot;'$(var model)'=='model_64'&quot;)" name="base_name" default="hdl-64"/>
Expand All @@ -24,5 +25,8 @@
<param name="precision" value="$(var precision)"/>
<param name="target_frame" value="$(var target_frame)"/>
<param from="$(var param_file)"/>

<!-- This parameter shall NOT be included in param file. -->
<param name="build_only" value="$(var build_only)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,11 @@
return;
}

if (node_->declare_parameter("build_only", false)) {
RCLCPP_INFO(node_->get_logger(), "TensorRT engine is built and shutdown node.");
rclcpp::shutdown();

Check warning on line 53 in perception/lidar_apollo_instance_segmentation/src/detector.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_apollo_instance_segmentation/src/detector.cpp#L51-L53

Added lines #L51 - L53 were not covered by tests
}

// GPU memory allocation
const auto input_dims = trt_common_->getBindingDimensions(0);
const auto input_size =
Expand Down
Loading