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

chore: sync awf-latest #1847

Merged
merged 1 commit into from
Feb 19, 2025
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
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,4 @@
ros__parameters:
publish_amplitude_pointcloud: true
publish_doppler_pointcloud: false
max_queue_size: 5
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,15 @@
"type": "boolean",
"description": "Whether publish radar pointcloud whose intensity is doppler velocity.",
"default": "false"
},
"max_queue_size": {
"type": "integer",
"default": "5",
"minimum": 1,
"description": "Max queue size of input/output topics."
}
},
"required": ["publish_amplitude_pointcloud", "publish_doppler_pointcloud"]
"required": ["publish_amplitude_pointcloud", "publish_doppler_pointcloud", "max_queue_size"]
}
},
"properties": {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,19 +106,23 @@ RadarScanToPointcloud2Node::RadarScanToPointcloud2Node(const rclcpp::NodeOptions
node_param_.publish_amplitude_pointcloud =
declare_parameter<bool>("publish_amplitude_pointcloud");
node_param_.publish_doppler_pointcloud = declare_parameter<bool>("publish_doppler_pointcloud");
node_param_.max_queue_size = declare_parameter<int64_t>("max_queue_size");

// Subscriber
sub_radar_ = create_subscription<RadarScan>(
"~/input/radar", rclcpp::QoS{1}, std::bind(&RadarScanToPointcloud2Node::onData, this, _1));
"~/input/radar", rclcpp::SensorDataQoS().keep_last(node_param_.max_queue_size),
std::bind(&RadarScanToPointcloud2Node::onData, this, _1));

{
rclcpp::PublisherOptions pub_options;
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
// Publisher
pub_amplitude_pointcloud_ =
create_publisher<PointCloud2>("~/output/amplitude_pointcloud", 1, pub_options);
pub_doppler_pointcloud_ =
create_publisher<PointCloud2>("~/output/doppler_pointcloud", 1, pub_options);
pub_amplitude_pointcloud_ = create_publisher<PointCloud2>(
"~/output/amplitude_pointcloud",
rclcpp::SensorDataQoS().keep_last(node_param_.max_queue_size), pub_options);
pub_doppler_pointcloud_ = create_publisher<PointCloud2>(
"~/output/doppler_pointcloud", rclcpp::SensorDataQoS().keep_last(node_param_.max_queue_size),
pub_options);
}
}

Expand All @@ -131,6 +135,7 @@ rcl_interfaces::msg::SetParametersResult RadarScanToPointcloud2Node::onSetParam(
auto & p = node_param_;
update_param(params, "publish_amplitude_pointcloud", p.publish_amplitude_pointcloud);
update_param(params, "publish_doppler_pointcloud", p.publish_doppler_pointcloud);
update_param(params, "max_queue_size", p.max_queue_size);
} catch (const rclcpp::exceptions::InvalidParameterTypeException & e) {
result.successful = false;
result.reason = e.what();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ class RadarScanToPointcloud2Node : public rclcpp::Node
{
bool publish_amplitude_pointcloud{};
bool publish_doppler_pointcloud{};
size_t max_queue_size{};
};

private:
Expand Down
Loading