Skip to content

Commit ea8e0be

Browse files
committed
refactor: apply snake_case to the function names
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
1 parent 3ca78a4 commit ea8e0be

10 files changed

Lines changed: 63 additions & 149 deletions

mmrviz/include/mmrviz/color_map.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ class ColorMap
6262
return table_.at(idx);
6363
}
6464

65-
const cv::Mat & getLookUpTable() const noexcept { return lut_; }
65+
const cv::Mat & lookup_table() const noexcept { return lut_; }
6666

6767
private:
6868
std::array<cv::Scalar, num_color> table_;

mmrviz/include/mmrviz/visualizer/box_array2d_visualizer.hpp

Lines changed: 4 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -19,10 +19,7 @@
1919

2020
#include <image_transport/publisher.hpp>
2121
#include <image_transport/subscriber_filter.hpp>
22-
#include <rclcpp/node.hpp>
23-
#include <rclcpp/node_options.hpp>
24-
#include <rclcpp/qos.hpp>
25-
#include <rclcpp/timer.hpp>
22+
#include <rclcpp/rclcpp.hpp>
2623

2724
#include <mmros_msgs/msg/box_array2d.hpp>
2825
#include <sensor_msgs/msg/image.hpp>
@@ -43,15 +40,13 @@ class BoxArray2dVisualizer : public rclcpp::Node
4340
public:
4441
explicit BoxArray2dVisualizer(const rclcpp::NodeOptions & options);
4542

43+
private:
44+
void on_connect(bool use_raw);
45+
4646
void callback(
4747
const sensor_msgs::msg::Image::ConstSharedPtr image_msg,
4848
const mmros_msgs::msg::BoxArray2d::ConstSharedPtr boxes_msg);
4949

50-
private:
51-
void onConnect(bool use_raw);
52-
53-
std::optional<rclcpp::QoS> getTopicQos(const std::string & query_topic);
54-
5550
rclcpp::TimerBase::SharedPtr timer_;
5651
image_transport::SubscriberFilter image_sub_;
5752
message_filters::Subscriber<mmros_msgs::msg::BoxArray2d> boxes_sub_;

mmrviz/include/mmrviz/visualizer/box_array3d_visualizer.hpp

Lines changed: 9 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -19,10 +19,7 @@
1919

2020
#include <image_transport/publisher.hpp>
2121
#include <image_transport/subscriber_filter.hpp>
22-
#include <rclcpp/node.hpp>
23-
#include <rclcpp/node_options.hpp>
24-
#include <rclcpp/qos.hpp>
25-
#include <rclcpp/timer.hpp>
22+
#include <rclcpp/rclcpp.hpp>
2623

2724
#include <mmros_msgs/msg/box_array3d.hpp>
2825
#include <sensor_msgs/msg/camera_info.hpp>
@@ -54,6 +51,14 @@ class BoxArray3dVisualizer : public rclcpp::Node
5451
*/
5552
explicit BoxArray3dVisualizer(const rclcpp::NodeOptions & options);
5653

54+
private:
55+
/**
56+
* @brief Check connection and start subscribing topics.
57+
*
58+
* @param use_raw Indicates whether to use raw image.
59+
*/
60+
void on_connect(bool use_raw);
61+
5762
/**
5863
* @brief Render 3D boxes on the subscribed image.
5964
*
@@ -66,21 +71,6 @@ class BoxArray3dVisualizer : public rclcpp::Node
6671
const sensor_msgs::msg::CameraInfo::ConstSharedPtr & camera_info_msg,
6772
const mmros_msgs::msg::BoxArray3d::ConstSharedPtr & boxes_msg);
6873

69-
private:
70-
/**
71-
* @brief Check connection and start subscribing topics.
72-
*
73-
* @param use_raw Indicates whether to use raw image.
74-
*/
75-
void onConnect(bool use_raw);
76-
77-
/**
78-
* @brief Return the QoS of the specified topic.
79-
*
80-
* @param query_topic Topic name.
81-
*/
82-
std::optional<rclcpp::QoS> getTopicQos(const std::string & query_topic);
83-
8474
rclcpp::TimerBase::SharedPtr timer_; //!< Callback timer.
8575
image_transport::SubscriberFilter image_sub_; //!< Image subscription.
8676
message_filters::Subscriber<sensor_msgs::msg::CameraInfo>

mmrviz/include/mmrviz/visualizer/instance_segmentation2d_visualizer.hpp

Lines changed: 4 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -19,10 +19,7 @@
1919

2020
#include <image_transport/publisher.hpp>
2121
#include <image_transport/subscriber_filter.hpp>
22-
#include <rclcpp/node.hpp>
23-
#include <rclcpp/node_options.hpp>
24-
#include <rclcpp/qos.hpp>
25-
#include <rclcpp/timer.hpp>
22+
#include <rclcpp/rclcpp.hpp>
2623

2724
#include <mmros_msgs/msg/instance_segment_array2d.hpp>
2825
#include <sensor_msgs/msg/image.hpp>
@@ -45,15 +42,13 @@ class InstanceSegmentation2dVisualizer : public rclcpp::Node
4542

4643
explicit InstanceSegmentation2dVisualizer(const rclcpp::NodeOptions & options);
4744

45+
private:
46+
void on_connect(bool use_raw);
47+
4848
void callback(
4949
const image_type::ConstSharedPtr & image_msg,
5050
const segment_type::ConstSharedPtr & segments_msg);
5151

52-
private:
53-
void onConnect(bool use_raw);
54-
55-
std::optional<rclcpp::QoS> getTopicQos(const std::string & query_topic);
56-
5752
double mask_threshold_; //!< Threshold value for mask.
5853

5954
rclcpp::TimerBase::SharedPtr timer_; //!< Callback timer.

mmrviz/include/mmrviz/visualizer/segmentation2d_visualizer.hpp

Lines changed: 4 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -19,10 +19,7 @@
1919

2020
#include <image_transport/publisher.hpp>
2121
#include <image_transport/subscriber_filter.hpp>
22-
#include <rclcpp/node.hpp>
23-
#include <rclcpp/node_options.hpp>
24-
#include <rclcpp/qos.hpp>
25-
#include <rclcpp/timer.hpp>
22+
#include <rclcpp/rclcpp.hpp>
2623

2724
#include <sensor_msgs/msg/image.hpp>
2825

@@ -40,15 +37,13 @@ class Segmentation2dVisualizer : public rclcpp::Node
4037
public:
4138
explicit Segmentation2dVisualizer(const rclcpp::NodeOptions & options);
4239

40+
private:
41+
void on_connect(bool use_raw);
42+
4343
void callback(
4444
const sensor_msgs::msg::Image::ConstSharedPtr & image_msg,
4545
const sensor_msgs::msg::Image::ConstSharedPtr & mask_msg);
4646

47-
private:
48-
void onConnect(bool use_raw);
49-
50-
std::optional<rclcpp::QoS> getTopicQos(const std::string & query_topic);
51-
5247
rclcpp::TimerBase::SharedPtr timer_;
5348
image_transport::SubscriberFilter image_sub_;
5449
image_transport::SubscriberFilter mask_sub_;

mmrviz/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
<depend>cv_bridge</depend>
1313
<depend>image_geometry</depend>
1414
<depend>image_transport</depend>
15+
<depend>mmros</depend>
1516
<depend>mmros_msgs</depend>
1617
<depend>rclcpp</depend>
1718
<depend>rclcpp_components</depend>

mmrviz/src/visualizer/box_array2d_visualizer.cpp

Lines changed: 9 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#include "mmrviz/visualizer/box_array2d_visualizer.hpp"
1616

1717
#include <image_transport/image_transport.hpp>
18+
#include <mmros/node/utility.hpp>
1819
#include <opencv2/core/mat.hpp>
1920
#include <opencv2/core/operations.hpp>
2021
#include <opencv2/core/types.hpp>
@@ -44,27 +45,20 @@ BoxArray2dVisualizer::BoxArray2dVisualizer(const rclcpp::NodeOptions & options)
4445
using std::chrono_literals::operator""ms;
4546

4647
bool use_raw = declare_parameter<bool>("use_raw");
47-
timer_ =
48-
rclcpp::create_timer(this, get_clock(), 100ms, [this, use_raw]() { this->onConnect(use_raw); });
48+
timer_ = rclcpp::create_timer(
49+
this, get_clock(), 100ms, [this, use_raw]() { this->on_connect(use_raw); });
4950

5051
pub_ = image_transport::create_publisher(this, "~/output/image");
5152
}
5253

53-
void BoxArray2dVisualizer::onConnect(bool use_raw)
54+
void BoxArray2dVisualizer::on_connect(bool use_raw)
5455
{
55-
auto resolve_topic_name = [this](const std::string & query) {
56-
return this->get_node_topics_interface()->resolve_topic_name(query);
57-
};
58-
59-
const auto image_topic = resolve_topic_name("~/input/image");
60-
auto image_topic_for_qos_query = image_topic;
61-
if (!use_raw) {
62-
image_topic_for_qos_query += "/compressed";
63-
}
64-
const auto image_qos = getTopicQos(image_topic_for_qos_query);
56+
const auto image_topic = mmros::node::resolve_topic_name(this, "~/input/image");
57+
const auto image_qos = use_raw ? mmros::node::to_topic_qos(this, image_topic)
58+
: mmros::node::to_topic_qos(this, image_topic + "/compressed");
6559

66-
const auto boxes_topic = resolve_topic_name("~/input/boxes");
67-
const auto boxes_qos = getTopicQos(boxes_topic);
60+
const auto boxes_topic = mmros::node::resolve_topic_name(this, "~/input/boxes");
61+
const auto boxes_qos = mmros::node::to_topic_qos(this, boxes_topic);
6862

6963
if (image_qos && boxes_qos) {
7064
const auto transport = use_raw ? "raw" : "compressed";
@@ -77,16 +71,6 @@ void BoxArray2dVisualizer::onConnect(bool use_raw)
7771
}
7872
}
7973

80-
std::optional<rclcpp::QoS> BoxArray2dVisualizer::getTopicQos(const std::string & query_topic)
81-
{
82-
const auto publisher_info = get_publishers_info_by_topic(query_topic);
83-
if (publisher_info.size() != 1) {
84-
return {};
85-
} else {
86-
return publisher_info[0].qos_profile();
87-
}
88-
}
89-
9074
void BoxArray2dVisualizer::callback(
9175
const sensor_msgs::msg::Image::ConstSharedPtr image_msg,
9276
const mmros_msgs::msg::BoxArray2d::ConstSharedPtr boxes_msg)

mmrviz/src/visualizer/box_array3d_visualizer.cpp

Lines changed: 11 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#include "mmrviz/visualizer/box_array3d_visualizer.hpp"
1616

1717
#include <image_transport/image_transport.hpp>
18+
#include <mmros/node/utility.hpp>
1819
#include <opencv2/core/mat.hpp>
1920
#include <opencv2/core/operations.hpp>
2021
#include <opencv2/core/types.hpp>
@@ -185,30 +186,23 @@ BoxArray3dVisualizer::BoxArray3dVisualizer(const rclcpp::NodeOptions & options)
185186
using std::chrono_literals::operator""ms;
186187

187188
bool use_raw = declare_parameter<bool>("use_raw");
188-
timer_ =
189-
rclcpp::create_timer(this, get_clock(), 100ms, [this, use_raw]() { this->onConnect(use_raw); });
189+
timer_ = rclcpp::create_timer(
190+
this, get_clock(), 100ms, [this, use_raw]() { this->on_connect(use_raw); });
190191

191192
pub_ = image_transport::create_publisher(this, "~/output/image");
192193
}
193194

194-
void BoxArray3dVisualizer::onConnect(bool use_raw)
195+
void BoxArray3dVisualizer::on_connect(bool use_raw)
195196
{
196-
auto resolve_topic_name = [this](const std::string & query) {
197-
return this->get_node_topics_interface()->resolve_topic_name(query);
198-
};
199-
200-
const auto image_topic = resolve_topic_name("~/input/image");
201-
auto image_topic_for_qos_query = image_topic;
202-
if (!use_raw) {
203-
image_topic_for_qos_query += "/compressed";
204-
}
205-
const auto image_qos = getTopicQos(image_topic_for_qos_query);
197+
const auto image_topic = mmros::node::resolve_topic_name(this, "~/input/image");
198+
const auto image_qos = use_raw ? mmros::node::to_topic_qos(this, image_topic)
199+
: mmros::node::to_topic_qos(this, image_topic + "/compressed");
206200

207-
const auto camera_info_topic = resolve_topic_name("~/input/camera_info");
208-
const auto camera_info_qos = getTopicQos(camera_info_topic);
201+
const auto camera_info_topic = mmros::node::resolve_topic_name(this, "~/input/camera_info");
202+
const auto camera_info_qos = mmros::node::to_topic_qos(this, camera_info_topic);
209203

210-
const auto boxes_topic = resolve_topic_name("~/input/boxes");
211-
const auto boxes_qos = getTopicQos(boxes_topic);
204+
const auto boxes_topic = mmros::node::resolve_topic_name(this, "~/input/boxes");
205+
const auto boxes_qos = mmros::node::to_topic_qos(this, boxes_topic);
212206

213207
bool is_image_ok = image_qos.has_value();
214208
bool is_camera_info_ok = camera_info_qos.has_value();
@@ -228,16 +222,6 @@ void BoxArray3dVisualizer::onConnect(bool use_raw)
228222
}
229223
}
230224

231-
std::optional<rclcpp::QoS> BoxArray3dVisualizer::getTopicQos(const std::string & query_topic)
232-
{
233-
const auto publishers_info = get_publishers_info_by_topic(query_topic);
234-
if (publishers_info.size() != 1) {
235-
return std::nullopt;
236-
} else {
237-
return publishers_info[0].qos_profile();
238-
}
239-
}
240-
241225
void BoxArray3dVisualizer::callback(
242226
const sensor_msgs::msg::Image::ConstSharedPtr & image_msg,
243227
const sensor_msgs::msg::CameraInfo::ConstSharedPtr & camera_info_msg,

mmrviz/src/visualizer/instance_segmentation2d_visualizer.cpp

Lines changed: 10 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include "mmrviz/color_map.hpp"
1818

1919
#include <image_transport/image_transport.hpp>
20+
#include <mmros/node/utility.hpp>
2021
#include <opencv2/core.hpp>
2122
#include <opencv2/core/mat.hpp>
2223
#include <opencv2/core/matx.hpp>
@@ -44,24 +45,20 @@ InstanceSegmentation2dVisualizer::InstanceSegmentation2dVisualizer(
4445
mask_threshold_ = declare_parameter<double>("mask_threshold", 0.8);
4546

4647
bool use_raw = declare_parameter<bool>("use_raw");
47-
timer_ =
48-
rclcpp::create_timer(this, get_clock(), 100ms, [this, use_raw]() { this->onConnect(use_raw); });
48+
timer_ = rclcpp::create_timer(
49+
this, get_clock(), 100ms, [this, use_raw]() { this->on_connect(use_raw); });
4950

5051
pub_ = image_transport::create_publisher(this, "~/output/image");
5152
}
5253

53-
void InstanceSegmentation2dVisualizer::onConnect(bool use_raw)
54+
void InstanceSegmentation2dVisualizer::on_connect(bool use_raw)
5455
{
55-
auto resolve_topic_name = [this](const std::string & query) {
56-
return this->get_node_topics_interface()->resolve_topic_name(query);
57-
};
56+
const auto image_topic = mmros::node::resolve_topic_name(this, "~/input/image");
57+
const auto image_qos = use_raw ? mmros::node::to_topic_qos(this, image_topic)
58+
: mmros::node::to_topic_qos(this, image_topic + "/compressed");
5859

59-
const auto image_topic = resolve_topic_name("~/input/image");
60-
const auto image_qos =
61-
use_raw ? getTopicQos(image_topic) : getTopicQos(image_topic + "/compressed");
62-
63-
const auto segments_topic = resolve_topic_name("~/input/segments");
64-
const auto segments_qos = getTopicQos(segments_topic);
60+
const auto segments_topic = mmros::node::resolve_topic_name(this, "~/input/segments");
61+
const auto segments_qos = mmros::node::to_topic_qos(this, segments_topic);
6562

6663
if (image_qos && segments_qos) {
6764
const auto transport = use_raw ? "raw" : "compressed";
@@ -75,17 +72,6 @@ void InstanceSegmentation2dVisualizer::onConnect(bool use_raw)
7572
}
7673
}
7774

78-
std::optional<rclcpp::QoS> InstanceSegmentation2dVisualizer::getTopicQos(
79-
const std::string & query_topic)
80-
{
81-
const auto publishers_info = get_publishers_info_by_topic(query_topic);
82-
if (publishers_info.size() != 1) {
83-
return std::nullopt;
84-
} else {
85-
return publishers_info[0].qos_profile();
86-
}
87-
}
88-
8975
void InstanceSegmentation2dVisualizer::callback(
9076
const image_type::ConstSharedPtr & image_msg, const segment_type::ConstSharedPtr & segments_msg)
9177
{
@@ -97,7 +83,7 @@ void InstanceSegmentation2dVisualizer::callback(
9783
return;
9884
}
9985

100-
const auto & lut = color_map_.getLookUpTable();
86+
const auto & lut = color_map_.lookup_table();
10187
auto & image = in_image_ptr->image;
10288
for (size_t i = 0; i < segments_msg->segments.size(); ++i) {
10389
const auto & box = segments_msg->segments[i].box;

0 commit comments

Comments
 (0)