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

Sort up ROS parameters for filter chains #199

Merged
merged 2 commits into from
Jul 23, 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
23 changes: 12 additions & 11 deletions src/scan_to_cloud_filter_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,21 +51,22 @@ ScanToCloudFilterChain::ScanToCloudFilterChain(
cloud_filter_chain_("sensor_msgs::msg::PointCloud2"),
scan_filter_chain_("sensor_msgs::msg::LaserScan")
{
this->declare_parameter("high_fidelity", false);
this->declare_parameter("notifier_tolerance", 0.03);
this->declare_parameter("target_frame", std::string("base_link"));
this->declare_parameter("incident_angle_correction", true);

rcl_interfaces::msg::ParameterDescriptor read_only_desc;
read_only_desc.read_only = true;

// Declare parameters
this->declare_parameter("high_fidelity", false, read_only_desc);
this->declare_parameter("notifier_tolerance", 0.03, read_only_desc);
this->declare_parameter("target_frame", "base_link", read_only_desc);
this->declare_parameter("incident_angle_correction", true, read_only_desc);
this->declare_parameter("laser_max_range", DBL_MAX, read_only_desc);

// Get parameters
this->get_parameter("high_fidelity", high_fidelity_);
this->get_parameter("notifier_tolerance", tf_tolerance_);
this->get_parameter("target_frame", target_frame_);
this->get_parameter("incident_angle_correction", incident_angle_correction_);

this->get_parameter_or("filter_window", window_, 2);
this->get_parameter_or("laser_max_range", laser_max_range_, DBL_MAX);
this->get_parameter_or("scan_topic", scan_topic_, std::string("tilt_scan"));
this->get_parameter_or("cloud_topic", cloud_topic_, std::string("tilt_laser_cloud_filtered"));

this->get_parameter("laser_max_range", laser_max_range_);

filter_.setTargetFrame(target_frame_);
filter_.registerCallback(
Expand Down
13 changes: 5 additions & 8 deletions src/scan_to_cloud_filter_chain.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,26 +58,23 @@ class ScanToCloudFilterChain : public rclcpp::Node
// ROS related
laser_geometry::LaserProjection projector_; // Used to project laser scans

double laser_max_range_; // Used in laser scan projection
int window_;

bool high_fidelity_; // High fidelity (interpolating time across scan)
std::string target_frame_; // Target frame for high fidelity result
std::string scan_topic_, cloud_topic_;

// TF
tf2_ros::Buffer buffer_;
tf2_ros::TransformListener tf_;

message_filters::Subscriber<sensor_msgs::msg::LaserScan> sub_;
tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan> filter_;

double tf_tolerance_;
filters::FilterChain<sensor_msgs::msg::PointCloud2> cloud_filter_chain_;
filters::FilterChain<sensor_msgs::msg::LaserScan> scan_filter_chain_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr cloud_pub_;

// Parameters
bool high_fidelity_; // High fidelity (interpolating time across scan)
double tf_tolerance_;
std::string target_frame_; // Target frame for high fidelity result
bool incident_angle_correction_;
double laser_max_range_; // Used in laser scan projection

ScanToCloudFilterChain(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions(),
Expand Down
15 changes: 11 additions & 4 deletions src/scan_to_scan_filter_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,17 +47,24 @@ ScanToScanFilterChain::ScanToScanFilterChain(
"",
this->get_node_logging_interface(), this->get_node_parameters_interface());

std::string tf_message_filter_target_frame;
if (this->get_parameter("tf_message_filter_target_frame", tf_message_filter_target_frame)) {
rcl_interfaces::msg::ParameterDescriptor read_only_desc;
read_only_desc.read_only = true;

this->get_parameter_or("tf_message_filter_tolerance", tf_filter_tolerance_, 0.03);
// Declare parameters
this->declare_parameter("tf_message_filter_target_frame", "", read_only_desc);
this->declare_parameter("tf_message_filter_tolerance", 0.03, read_only_desc);

// Get parameters
this->get_parameter("tf_message_filter_target_frame", tf_message_filter_target_frame_);
this->get_parameter("tf_message_filter_tolerance", tf_filter_tolerance_);

if (!tf_message_filter_target_frame_.empty()) {
tf_.reset(new tf2_ros::TransformListener(buffer_));
tf_filter_.reset(
new tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>(
scan_sub_, buffer_, "",
50, this->get_node_logging_interface(), this->get_node_clock_interface()));
tf_filter_->setTargetFrame(tf_message_filter_target_frame);
tf_filter_->setTargetFrame(tf_message_filter_target_frame_);
tf_filter_->setTolerance(std::chrono::duration<double>(tf_filter_tolerance_));

// Setup tf::MessageFilter generates callback
Expand Down
5 changes: 4 additions & 1 deletion src/scan_to_scan_filter_chain.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,6 @@ class ScanToScanFilterChain : public rclcpp::Node

message_filters::Subscriber<sensor_msgs::msg::LaserScan> scan_sub_;
std::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> tf_filter_;
double tf_filter_tolerance_;

// Filter Chain
filters::FilterChain<sensor_msgs::msg::LaserScan> filter_chain_;
Expand All @@ -58,6 +57,10 @@ class ScanToScanFilterChain : public rclcpp::Node
sensor_msgs::msg::LaserScan msg_;
rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr output_pub_;

// Parameters
std::string tf_message_filter_target_frame_;
double tf_filter_tolerance_;

public:
// Constructor
ScanToScanFilterChain(
Expand Down
Loading