Skip to content

Commit

Permalink
fix: read float param (#1357)
Browse files Browse the repository at this point in the history
* read float param

Signed-off-by: suchang <[email protected]>

* remove cout

Signed-off-by: suchang <[email protected]>

* change default z_offset

Signed-off-by: suchang <[email protected]>

Co-authored-by: suchang <[email protected]>
  • Loading branch information
storrrrrrrrm and suchang authored Jul 18, 2022
1 parent f603772 commit 9ab2d2f
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
<arg name="param_file" default="$(find-pkg-share lidar_apollo_instance_segmentation)/config/$(var base_name).param.yaml"/>

<arg name="target_frame" default="base_link"/>
<arg name="z_offset" default="-2"/>
<arg name="z_offset" default="-2.0"/>

<node pkg="lidar_apollo_instance_segmentation" exec="lidar_apollo_instance_segmentation_node" name="lidar_apollo_instance_segmentation" output="screen">
<remap from="input/pointcloud" to="$(var input/pointcloud)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node *
use_intensity_feature = node_->declare_parameter("use_intensity_feature", true);
use_constant_feature = node_->declare_parameter("use_constant_feature", true);
target_frame_ = node_->declare_parameter("target_frame", "base_link");
z_offset_ = node_->declare_parameter("z_offset", 2);
z_offset_ = node_->declare_parameter<float>("z_offset", -2.0);

// load weight file
std::ifstream fs(engine_file);
Expand Down

0 comments on commit 9ab2d2f

Please sign in to comment.