Skip to content

Commit

Permalink
create launch and config
Browse files Browse the repository at this point in the history
Signed-off-by: Autumn60 <[email protected]>
  • Loading branch information
Autumn60 committed Aug 10, 2024
1 parent b04214d commit 50610e0
Show file tree
Hide file tree
Showing 5 changed files with 26 additions and 5 deletions.
Empty file.
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
/**:
ros__parameters:
footprint_frame: base_link
leaf_size: 0.1
distance_threshold: 0.3
max_iterations: 1000
slope_threshold: 10.0
Empty file.
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
<launch>
<arg name="method" default="ransac"/>

<arg name="input_points_topic" default="/velodyne_points"/>
<arg name="output_points_topic" default="/velodyne_points/obstacle"/>

<arg name="config_file" default="$(find-pkg-share ground_segmentation)/config/$(var method)_ground_filter.param.yaml"/>

<node pkg="ground_segmentation" name="$(var method)_ground_filter" exec="$(var method)_ground_filter_node" output="screen">
<remap from="~/input/points" to="$(var input_points_topic)"/>
<remap from="~/output/points" to="$(var output_points_topic)"/>
<param from="$(var config_file)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,11 @@ namespace ground_segmentation::ransac_ground_filter
RANSACGroundFilter::RANSACGroundFilter(const rclcpp::NodeOptions & options)
: GroundFilter("ransac_ground_filter", options)
{
footprint_frame_ = get_parameter("footprint_frame").as_string();
leaf_size_ = get_parameter("leaf_size").as_double();
distance_threshold_ = get_parameter("distance_threshold").as_double();
max_iterations_ = get_parameter("max_iterations").as_int();
slope_threshold_rad_ = get_parameter("slope_threshold").as_double() * M_PI / 180.0;
footprint_frame_ = declare_parameter<std::string>("footprint_frame", "base_link");
leaf_size_ = declare_parameter<double>("leaf_size", 0.1);
distance_threshold_ = declare_parameter<double>("distance_threshold", 0.1);
max_iterations_ = declare_parameter<int>("max_iterations", 1000);
slope_threshold_rad_ = declare_parameter<double>("slope_threshold", 10.0) * M_PI / 180.0;
}

bool RANSACGroundFilter::filter(const PointCloud2 & input, PointCloud2 & output)
Expand Down

0 comments on commit 50610e0

Please sign in to comment.