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

Fix/ros2 build param issues #1

Merged
merged 3 commits into from
Nov 13, 2023
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: 0 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -63,5 +63,4 @@ The default parameters should work on the KITTI dataset.
### Other

- **n_threads** Number of threads to use.
- **latch** Latch output point clouds in ROS node.
- **visualize** Visualize the segmentation result. **ONLY FOR DEBUGGING.** Do not set true during online operation.
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,12 @@ struct GroundSegmentationParams {
double line_search_angle;
// Number of threads.
int n_threads;
// Minimum point distance.
double r_min;
// Maximum point distance.
double r_max;
// Maximum error of a point during line fit.
double max_fit_error;
};

typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@ ground_segmentation:

gravity_aligned_frame: "" # Frame which has its z axis aligned with gravity. (Sensor frame if empty.)

latch: false # latch output topics or not
visualize: false # visualize segmentation result - USE ONLY FOR DEBUGGING

input_topic: "livox/lidar/pointcloud"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <pcl/common/transforms.h>
#include <pcl/io/ply_io.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl_ros/point_cloud.h>
// #include <pcl_ros/point_cloud.hpp>
#include <rclcpp/qos.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
Expand Down Expand Up @@ -52,6 +52,10 @@ SegmentationNode::SegmentationNode(const rclcpp::NodeOptions &node_options)
params_.line_search_angle =
this->declare_parameter("line_search_angle", params_.line_search_angle);
params_.n_threads = this->declare_parameter("n_threads", params_.n_threads);
params_.r_min = this->declare_parameter("r_min", params_.r_min);
params_.r_max = this->declare_parameter("r_max", params_.r_max);
params_.max_fit_error =
this->declare_parameter("max_fit_error", params_.max_fit_error);
// Params that need to be squared.
double r_min, r_max, max_fit_error;
if (this->get_parameter("r_min", r_min)) {
Expand Down Expand Up @@ -81,6 +85,8 @@ SegmentationNode::SegmentationNode(const rclcpp::NodeOptions &node_options)
tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
RCLCPP_INFO(this->get_logger(), "Segmentation node initialized");
RCLCPP_INFO(this->get_logger(), "params_.r_min_square: %f",
params_.r_min_square);
}

void SegmentationNode::scanCallback(
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#include <pcl/io/ply_io.h>
#include <pcl_ros/point_cloud.h>
// #include <pcl_ros/point_cloud.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>

Expand Down Expand Up @@ -34,6 +34,10 @@ int main(int argc, char **argv) {
params.line_search_angle =
node->declare_parameter("line_search_angle", params.line_search_angle);
params.n_threads = node->declare_parameter("n_threads", params.n_threads);
params.r_min = node->declare_parameter("r_min", params.r_min);
params.r_max = node->declare_parameter("r_max", params.r_max);
params.max_fit_error =
node->declare_parameter("max_fit_error", params.max_fit_error);
// Params that need to be squared.
double r_min, r_max, max_fit_error;
if (node->get_parameter("r_min", r_min)) {
Expand Down