Skip to content

Commit

Permalink
linting
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson committed Nov 14, 2023
1 parent e8e8c84 commit 2484f5f
Show file tree
Hide file tree
Showing 11 changed files with 51 additions and 78 deletions.
12 changes: 5 additions & 7 deletions depth_image_proc/src/convert_metric.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,23 +67,21 @@ ConvertMetricNode::ConvertMetricNode(const rclcpp::NodeOptions & options)
// Create publisher with connect callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo&)
[this](rclcpp::MatchedInfo &)
{
std::lock_guard<std::mutex> lock(connect_mutex_);
if (pub_depth_.getNumSubscribers() == 0)
{
if (pub_depth_.getNumSubscribers() == 0) {
sub_raw_.shutdown();
}
else if (!sub_raw_)
{
} else if (!sub_raw_) {
image_transport::TransportHints hints(this, "raw");
sub_raw_ = image_transport::create_subscription(
this, "image_raw",
std::bind(&ConvertMetricNode::depthCb, this, std::placeholders::_1),
hints.getTransport());
}
};
pub_depth_ = image_transport::create_publisher(this, "image", rmw_qos_profile_default, pub_options);
pub_depth_ =
image_transport::create_publisher(this, "image", rmw_qos_profile_default, pub_options);
}

void ConvertMetricNode::depthCb(const sensor_msgs::msg::Image::ConstSharedPtr & raw_msg)
Expand Down
13 changes: 6 additions & 7 deletions depth_image_proc/src/point_cloud_xyz.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,22 +57,21 @@ PointCloudXyzNode::PointCloudXyzNode(const rclcpp::NodeOptions & options)
// Create publisher with connect callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo& s)
[this](rclcpp::MatchedInfo & s)
{
std::lock_guard<std::mutex> lock(connect_mutex_);
if (s.current_count == 0)
{
if (s.current_count == 0) {
sub_depth_.shutdown();
}
else if (!sub_depth_)
{
} else if (!sub_depth_) {
auto custom_qos = rmw_qos_profile_system_default;
custom_qos.depth = queue_size_;

sub_depth_ = image_transport::create_camera_subscription(
this,
"image_rect",
std::bind(&PointCloudXyzNode::depthCb, this, std::placeholders::_1, std::placeholders::_2),
std::bind(
&PointCloudXyzNode::depthCb, this, std::placeholders::_1,
std::placeholders::_2),
"raw",
custom_qos);
}
Expand Down
12 changes: 5 additions & 7 deletions depth_image_proc/src/point_cloud_xyz_radial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,15 +56,12 @@ PointCloudXyzRadialNode::PointCloudXyzRadialNode(const rclcpp::NodeOptions & opt
// Create publisher with connect callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo& s)
[this](rclcpp::MatchedInfo & s)
{
std::lock_guard<std::mutex> lock(connect_mutex_);
if (s.current_count == 0)
{
if (s.current_count == 0) {
sub_depth_.shutdown();
}
else if (!sub_depth_)
{
} else if (!sub_depth_) {
auto custom_qos = rmw_qos_profile_system_default;
custom_qos.depth = queue_size_;

Expand All @@ -78,7 +75,8 @@ PointCloudXyzRadialNode::PointCloudXyzRadialNode(const rclcpp::NodeOptions & opt
custom_qos);
}
};
pub_point_cloud_ = create_publisher<sensor_msgs::msg::PointCloud2>("points", rclcpp::SensorDataQoS(), pub_options);
pub_point_cloud_ = create_publisher<sensor_msgs::msg::PointCloud2>(
"points", rclcpp::SensorDataQoS(), pub_options);
}

void PointCloudXyzRadialNode::depthCb(
Expand Down
9 changes: 3 additions & 6 deletions depth_image_proc/src/point_cloud_xyzi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,17 +74,14 @@ PointCloudXyziNode::PointCloudXyziNode(const rclcpp::NodeOptions & options)
// Create publisher with connect callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo& s)
[this](rclcpp::MatchedInfo & s)
{
std::lock_guard<std::mutex> lock(connect_mutex_);
if (s.current_count == 0)
{
if (s.current_count == 0) {
sub_depth_.unsubscribe();
sub_intensity_.unsubscribe();
sub_info_.unsubscribe();
}
else if (!sub_depth_.getSubscriber())
{
} else if (!sub_depth_.getSubscriber()) {
// parameter for depth_image_transport hint
std::string depth_image_transport_param = "depth_image_transport";

Expand Down
12 changes: 5 additions & 7 deletions depth_image_proc/src/point_cloud_xyzi_radial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,17 +72,14 @@ PointCloudXyziRadialNode::PointCloudXyziRadialNode(const rclcpp::NodeOptions & o
// Create publisher with connect callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo& s)
[this](rclcpp::MatchedInfo & s)
{
std::lock_guard<std::mutex> lock(connect_mutex_);
if (s.current_count == 0)
{
if (s.current_count == 0) {
sub_depth_.unsubscribe();
sub_intensity_.unsubscribe();
sub_info_.unsubscribe();
}
else if (!sub_depth_.getSubscriber())
{
} else if (!sub_depth_.getSubscriber()) {
// parameter for depth_image_transport hint
std::string depth_image_transport_param = "depth_image_transport";

Expand All @@ -96,7 +93,8 @@ PointCloudXyziRadialNode::PointCloudXyziRadialNode(const rclcpp::NodeOptions & o
sub_info_.subscribe(this, "intensity/camera_info");
}
};
pub_point_cloud_ = create_publisher<sensor_msgs::msg::PointCloud2>("points", rclcpp::SensorDataQoS(), pub_options);
pub_point_cloud_ = create_publisher<sensor_msgs::msg::PointCloud2>(
"points", rclcpp::SensorDataQoS(), pub_options);
}

void PointCloudXyziRadialNode::imageCb(
Expand Down
9 changes: 3 additions & 6 deletions depth_image_proc/src/point_cloud_xyzrgb.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,17 +83,14 @@ PointCloudXyzrgbNode::PointCloudXyzrgbNode(const rclcpp::NodeOptions & options)
// Create publisher with connect callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo& s)
[this](rclcpp::MatchedInfo & s)
{
std::lock_guard<std::mutex> lock(connect_mutex_);
if (s.current_count == 0)
{
if (s.current_count == 0) {
sub_depth_.unsubscribe();
sub_rgb_.unsubscribe();
sub_info_.unsubscribe();
}
else if (!sub_depth_.getSubscriber())
{
} else if (!sub_depth_.getSubscriber()) {
// parameter for depth_image_transport hint
std::string depth_image_transport_param = "depth_image_transport";
image_transport::TransportHints depth_hints(this, "raw", depth_image_transport_param);
Expand Down
9 changes: 3 additions & 6 deletions depth_image_proc/src/point_cloud_xyzrgb_radial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,17 +87,14 @@ PointCloudXyzrgbRadialNode::PointCloudXyzrgbRadialNode(const rclcpp::NodeOptions
// Create publisher with connect callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo& s)
[this](rclcpp::MatchedInfo & s)
{
std::lock_guard<std::mutex> lock(connect_mutex_);
if (s.current_count == 0)
{
if (s.current_count == 0) {
sub_depth_.unsubscribe();
sub_rgb_.unsubscribe();
sub_info_.unsubscribe();
}
else if (!sub_depth_.getSubscriber())
{
} else if (!sub_depth_.getSubscriber()) {
// parameter for depth_image_transport hint
std::string depth_image_transport_param = "depth_image_transport";
image_transport::TransportHints depth_hints(this, "raw", depth_image_transport_param);
Expand Down
11 changes: 4 additions & 7 deletions image_proc/src/crop_decimate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,17 +130,14 @@ CropDecimateNode::CropDecimateNode(const rclcpp::NodeOptions & options)
// Create image pub with connection callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo&)
[this](rclcpp::MatchedInfo &)
{
if (pub_.getNumSubscribers() == 0)
{
if (pub_.getNumSubscribers() == 0) {
sub_.shutdown();
}
else if (!sub_)
{
} else if (!sub_) {
auto qos_profile = getTopicQosProfile(this, "in/image_raw");
sub_ = image_transport::create_camera_subscription(
this, "in/image_raw", std::bind(
this, "in/image_raw", std::bind(
&CropDecimateNode::imageCb, this,
std::placeholders::_1, std::placeholders::_2), "raw", qos_profile);
}
Expand Down
17 changes: 7 additions & 10 deletions image_proc/src/debayer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,20 +56,17 @@ DebayerNode::DebayerNode(const rclcpp::NodeOptions & options)
// Create publisher options to setup callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo&)
[this](rclcpp::MatchedInfo &)
{
if (pub_mono_.getNumSubscribers() == 0 && pub_color_.getNumSubscribers() == 0)
{
if (pub_mono_.getNumSubscribers() == 0 && pub_color_.getNumSubscribers() == 0) {
sub_raw_.shutdown();
}
else if (!sub_raw_)
{
} else if (!sub_raw_) {
auto qos_profile = getTopicQosProfile(this, "image_raw");
sub_raw_ = image_transport::create_subscription(
this, "image_raw",
std::bind(
&DebayerNode::imageCb, this,
std::placeholders::_1), "raw", qos_profile);
this, "image_raw",
std::bind(
&DebayerNode::imageCb, this,
std::placeholders::_1), "raw", qos_profile);
}
};
pub_mono_ = image_transport::create_publisher(this, "image_mono", qos_profile, pub_options);
Expand Down
13 changes: 5 additions & 8 deletions image_proc/src/rectify.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,19 +58,16 @@ RectifyNode::RectifyNode(const rclcpp::NodeOptions & options)
// Create publisher with connect callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo&)
[this](rclcpp::MatchedInfo &)
{
if (pub_rect_.getNumSubscribers() == 0)
{
if (pub_rect_.getNumSubscribers() == 0) {
sub_camera_.shutdown();
}
else if (!sub_camera_)
{
} else if (!sub_camera_) {
auto qos_profile = getTopicQosProfile(this, "image");
sub_camera_ = image_transport::create_camera_subscription(
this, "image", std::bind(
&RectifyNode::imageCb,
this, std::placeholders::_1, std::placeholders::_2), "raw", qos_profile);
&RectifyNode::imageCb,
this, std::placeholders::_1, std::placeholders::_2), "raw", qos_profile);
}
};
pub_rect_ = image_transport::create_publisher(this, "image_rect", qos_profile, pub_options);
Expand Down
12 changes: 5 additions & 7 deletions image_proc/src/resize.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,14 +55,11 @@ ResizeNode::ResizeNode(const rclcpp::NodeOptions & options)
// Create image pub with connection callback
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo&)
[this](rclcpp::MatchedInfo &)
{
if (pub_image_.getNumSubscribers() == 0)
{
if (pub_image_.getNumSubscribers() == 0) {
sub_image_.shutdown();
}
else if (!sub_image_)
{
} else if (!sub_image_) {
auto qos_profile = getTopicQosProfile(this, "image/image_raw");
sub_image_ = image_transport::create_camera_subscription(
this, "image/image_raw",
Expand All @@ -72,7 +69,8 @@ ResizeNode::ResizeNode(const rclcpp::NodeOptions & options)
std::placeholders::_2), "raw", qos_profile);
}
};
pub_image_ = image_transport::create_camera_publisher(this, "resize/image_raw", qos_profile, pub_options);
pub_image_ = image_transport::create_camera_publisher(
this, "resize/image_raw", qos_profile, pub_options);

interpolation_ = this->declare_parameter("interpolation", 1);
use_scale_ = this->declare_parameter("use_scale", true);
Expand Down

0 comments on commit 2484f5f

Please sign in to comment.