Skip to content

Commit 08adb06

Browse files
Merge pull request #3 from zycczy/optimization_type
optimization the message type define
2 parents c8ce1b1 + 8ae58d3 commit 08adb06

File tree

5 files changed

+116
-78
lines changed

5 files changed

+116
-78
lines changed
Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
// Copyright (c) 2024 Qualcomm Innovation Center, Inc. All rights reserved.
2+
// SPDX-License-Identifier: BSD-3-Clause-Clear
3+
4+
#ifndef QRB_ROS_BENCHMARK__QRB_MESSAGE_TYPES_HPP_
5+
#define QRB_ROS_BENCHMARK__QRB_MESSAGE_TYPES_HPP_
6+
7+
// Standard library
8+
#include <string>
9+
#include <vector>
10+
11+
// QRB ROS transport types
12+
#include "qrb_ros_transport_image_type/image.hpp"
13+
#include "qrb_ros_transport_imu_type/imu.hpp"
14+
#include "qrb_ros_transport_point_cloud2_type/point_cloud2.hpp"
15+
16+
// DMABUF transport types
17+
#include "dmabuf_transport/type/image.hpp"
18+
#include "dmabuf_transport/type/point_cloud2.hpp"
19+
20+
// ROS message types
21+
#include "sensor_msgs/msg/image.hpp"
22+
#include "sensor_msgs/msg/compressed_image.hpp"
23+
#include "qrb_ros_tensor_list_msgs/msg/tensor_list.hpp"
24+
25+
namespace qrb_ros
26+
{
27+
namespace benchmark
28+
{
29+
30+
// Common macro for creating ROS message subscriber
31+
#define FOR_EACH_ROS_MESSAGE_TYPE(MACRO) \
32+
MACRO(sensor_msgs::msg::Image) \
33+
MACRO(sensor_msgs::msg::CompressedImage) \
34+
MACRO(qrb_ros_tensor_list_msgs::msg::TensorList)
35+
36+
// Common macro for creating QRB transport type subscriber/publisher
37+
#define FOR_EACH_QRB_TRANSPORT_TYPE(MACRO) \
38+
MACRO("qrb_ros/transport/type/Image", qrb_ros::transport::type::Image) \
39+
MACRO("qrb_ros/transport/type/Imu", qrb_ros::transport::type::Imu)
40+
41+
// Common macro for creating dmabuf transport type subscriber/publisher
42+
#define FOR_EACH_DMABUF_TRANSPORT_TYPE(MACRO) \
43+
MACRO("dmabuf_transport/type/Image", dmabuf_transport::type::Image) \
44+
MACRO("dmabuf_transport/type/PointCloud2", dmabuf_transport::type::PointCloud2)
45+
46+
} // namespace benchmark
47+
} // namespace qrb_ros
48+
49+
#endif // QRB_ROS_BENCHMARK__QRB_MESSAGE_TYPES_HPP_

include/qrb_ros_benchmark/qrb_monitor_node.hpp

Lines changed: 5 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -4,18 +4,15 @@
44
#ifndef QRB_ROS_BENCHMARK__QRB_MONITOR_NODE_HPP_
55
#define QRB_ROS_BENCHMARK__QRB_MONITOR_NODE_HPP_
66

7+
// Standard library
78
#include <string>
89

10+
// ROS libraries
911
#include "rclcpp/rclcpp.hpp"
1012
#include "ros2_benchmark/monitor_node.hpp"
11-
#include "qrb_ros_transport_image_type/image.hpp"
12-
#include "qrb_ros_transport_imu_type/imu.hpp"
13-
#include "qrb_ros_transport_point_cloud2_type/point_cloud2.hpp"
14-
#include "dmabuf_transport/type/image.hpp"
15-
#include "dmabuf_transport/type/point_cloud2.hpp"
16-
#include "sensor_msgs/msg/image.hpp"
17-
#include "sensor_msgs/msg/compressed_image.hpp"
18-
#include "qrb_ros_tensor_list_msgs/msg/tensor_list.hpp"
13+
14+
// QRB message types (includes all necessary message type headers)
15+
#include "qrb_ros_benchmark/qrb_message_types.hpp"
1916

2017
namespace qrb_ros
2118
{
@@ -25,12 +22,10 @@ namespace benchmark
2522
class QrbMonitorNode : public ros2_benchmark::MonitorNode
2623
{
2724
public:
28-
2925
// QrbMonitorNode constructor.
3026
explicit QrbMonitorNode(const rclcpp::NodeOptions &);
3127

3228
private:
33-
3429
// Determine the format, request to create the corresponding type of subscriber.
3530
void create_monitor_subscriber();
3631

include/qrb_ros_benchmark/qrb_playback_node.hpp

Lines changed: 5 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -4,20 +4,17 @@
44
#ifndef QRB_ROS_BENCHMARK__QRB_PLAYBACK_NODE_HPP_
55
#define QRB_ROS_BENCHMARK__QRB_PLAYBACK_NODE_HPP_
66

7+
// Standard library
78
#include <string>
89
#include <unordered_map>
910
#include <vector>
1011

12+
// ROS libraries
1113
#include "rclcpp/rclcpp.hpp"
1214
#include "ros2_benchmark/playback_node.hpp"
13-
#include "qrb_ros_transport_image_type/image.hpp"
14-
#include "qrb_ros_transport_imu_type/imu.hpp"
15-
#include "qrb_ros_transport_point_cloud2_type/point_cloud2.hpp"
16-
#include "dmabuf_transport/type/image.hpp"
17-
#include "dmabuf_transport/type/point_cloud2.hpp"
18-
#include "sensor_msgs/msg/image.hpp"
19-
#include "sensor_msgs/msg/compressed_image.hpp"
20-
#include "qrb_ros_tensor_list_msgs/msg/tensor_list.hpp"
15+
16+
// QRB message types (includes all necessary message type headers)
17+
#include "qrb_ros_benchmark/qrb_message_types.hpp"
2118

2219
namespace qrb_ros
2320
{
@@ -51,12 +48,10 @@ class MessageBuffer : public qrb_ros::benchmark::MessageBufferBase
5148
class QrbPlaybackNode : public ros2_benchmark::PlaybackNode
5249
{
5350
public:
54-
5551
// QrbPlaybackNode constructor.
5652
explicit QrbPlaybackNode(const rclcpp::NodeOptions &);
5753

5854
private:
59-
6055
// Check if the messages buffer is full for request size.
6156
bool AreBuffersFull() const override;
6257

@@ -79,7 +74,6 @@ class QrbPlaybackNode : public ros2_benchmark::PlaybackNode
7974
// Return publishers count number.
8075
size_t GetPublisherCount() const override;
8176

82-
8377
// Determine the format, request to create the corresponding type of pub and sub.
8478
void create_playback_pubsub(const size_t index, const std::string format);
8579

src/qrb_monitor_node.cpp

Lines changed: 21 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22
// SPDX-License-Identifier: BSD-3-Clause-Clear
33

44
#include "qrb_ros_benchmark/qrb_monitor_node.hpp"
5+
#include "qrb_ros_benchmark/qrb_message_types.hpp"
56
#include "rclcpp_components/register_node_macro.hpp"
67

78
using std::placeholders::_1;
@@ -21,26 +22,29 @@ QrbMonitorNode::QrbMonitorNode(const rclcpp::NodeOptions & options)
2122
void QrbMonitorNode::create_monitor_subscriber()
2223
{
2324
RCLCPP_INFO(this->get_logger(), "Monitor data format=\"%s\"", monitor_data_format_.c_str());
24-
// Create transport type subscriber
25-
if (monitor_data_format_.compare("qrb_ros/transport/type/Image") == 0) {
26-
return create_message_subscriber<qrb_ros::transport::type::Image>();
27-
} else if (monitor_data_format_.compare("qrb_ros/transport/type/Imu") == 0) {
28-
return create_message_subscriber<qrb_ros::transport::type::Imu>();
29-
} else if (monitor_data_format_.compare("dmabuf_transport/type/Image") == 0) {
30-
return create_message_subscriber<dmabuf_transport::type::Image>();
31-
} else if (monitor_data_format_.compare("dmabuf_transport/type/PointCloud2") == 0) {
32-
return create_message_subscriber<dmabuf_transport::type::PointCloud2>();
33-
}
25+
26+
// Create transport type subscriber using common macros
27+
#define CREATE_QRB_TRANSPORT_SUB(format_str, msg_type) \
28+
if (monitor_data_format_.compare(format_str) == 0) { \
29+
return create_message_subscriber<msg_type>(); \
30+
}
31+
32+
FOR_EACH_QRB_TRANSPORT_TYPE(CREATE_QRB_TRANSPORT_SUB)
33+
34+
#define CREATE_DMABUF_TRANSPORT_SUB(format_str, msg_type) \
35+
if (monitor_data_format_.compare(format_str) == 0) { \
36+
return create_message_subscriber<msg_type>(); \
37+
}
38+
39+
FOR_EACH_DMABUF_TRANSPORT_TYPE(CREATE_DMABUF_TRANSPORT_SUB)
3440

3541
// Create ros message type subscriber
3642
#define CREATE_ROS_MESSAGE_SUBSCRIBER(ROS_MESSAGE) \
37-
if (rosidl_generator_traits::name<ROS_MESSAGE>() == monitor_data_format_) { \
38-
return create_message_subscriber<ROS_MESSAGE>(); \
39-
} \
40-
41-
CREATE_ROS_MESSAGE_SUBSCRIBER(sensor_msgs::msg::Image)
42-
CREATE_ROS_MESSAGE_SUBSCRIBER(sensor_msgs::msg::CompressedImage)
43-
CREATE_ROS_MESSAGE_SUBSCRIBER(qrb_ros_tensor_list_msgs::msg::TensorList)
43+
if (rosidl_generator_traits::name<ROS_MESSAGE>() == monitor_data_format_) { \
44+
return create_message_subscriber<ROS_MESSAGE>(); \
45+
}
46+
47+
FOR_EACH_ROS_MESSAGE_TYPE(CREATE_ROS_MESSAGE_SUBSCRIBER)
4448

4549
// Create generic type message subscriber(SerializedMessage)
4650
CreateGenericTypeMonitorSubscriber();

src/qrb_playback_node.cpp

Lines changed: 36 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22
// SPDX-License-Identifier: BSD-3-Clause-Clear
33

44
#include "qrb_ros_benchmark/qrb_playback_node.hpp"
5+
#include "qrb_ros_benchmark/qrb_message_types.hpp"
56
#include "rclcpp_components/register_node_macro.hpp"
67

78
using std::placeholders::_1;
@@ -52,31 +53,31 @@ void QrbPlaybackNode::create_playback_pubsub(const size_t index, const std::stri
5253
{
5354
RCLCPP_INFO(this->get_logger(), "Data format=\"%s\", index=%ld", format.c_str(), index);
5455

55-
// Create transport_type pubsub
56-
if (format.compare("qrb_ros/transport/type/Image") == 0) {
57-
pub_sub_types_[index] = PubSubType::QrbTransportType;
58-
return create_message_pubsub<qrb_ros::transport::type::Image>(index, format);
59-
} else if (format.compare("qrb_ros/transport/type/Imu") == 0) {
60-
pub_sub_types_[index] = PubSubType::QrbTransportType;
61-
return create_message_pubsub<qrb_ros::transport::type::Imu>(index, format);
62-
} else if (format.compare("dmabuf_transport/type/Image") == 0) {
63-
pub_sub_types_[index] = PubSubType::DmabufTransportType;
64-
return create_message_pubsub<dmabuf_transport::type::Image>(index, format);
65-
} else if (format.compare("dmabuf_transport/type/PointCloud2") == 0) {
66-
pub_sub_types_[index] = PubSubType::DmabufTransportType;
67-
return create_message_pubsub<dmabuf_transport::type::PointCloud2>(index, format);
68-
}
56+
// Create transport_type pubsub using common macros
57+
#define CREATE_QRB_TRANSPORT_PUBSUB(format_str, msg_type) \
58+
if (format.compare(format_str) == 0) { \
59+
pub_sub_types_[index] = PubSubType::QrbTransportType; \
60+
return create_message_pubsub<msg_type>(index, format); \
61+
}
62+
63+
FOR_EACH_QRB_TRANSPORT_TYPE(CREATE_QRB_TRANSPORT_PUBSUB)
64+
65+
#define CREATE_DMABUF_TRANSPORT_PUBSUB(format_str, msg_type) \
66+
if (format.compare(format_str) == 0) { \
67+
pub_sub_types_[index] = PubSubType::DmabufTransportType; \
68+
return create_message_pubsub<msg_type>(index, format); \
69+
}
70+
71+
FOR_EACH_DMABUF_TRANSPORT_TYPE(CREATE_DMABUF_TRANSPORT_PUBSUB)
6972

7073
// Create ros message type pubsub
7174
#define CREATE_ROS_MESSAGE_PUBSUB(ROS_MESSAGE) \
72-
if (rosidl_generator_traits::name<ROS_MESSAGE>() == format) { \
73-
pub_sub_types_[index] = PubSubType::RosMessaageType; \
74-
return create_message_pubsub<ROS_MESSAGE>(index, format); \
75-
} \
76-
77-
CREATE_ROS_MESSAGE_PUBSUB(sensor_msgs::msg::Image)
78-
CREATE_ROS_MESSAGE_PUBSUB(sensor_msgs::msg::CompressedImage)
79-
CREATE_ROS_MESSAGE_PUBSUB(qrb_ros_tensor_list_msgs::msg::TensorList)
75+
if (rosidl_generator_traits::name<ROS_MESSAGE>() == format) { \
76+
pub_sub_types_[index] = PubSubType::RosMessaageType; \
77+
return create_message_pubsub<ROS_MESSAGE>(index, format); \
78+
}
79+
80+
FOR_EACH_ROS_MESSAGE_TYPE(CREATE_ROS_MESSAGE_PUBSUB)
8081

8182
// Create generic_type type pubsub
8283
pub_sub_types_[index] = PubSubType::GenericType;
@@ -260,31 +261,26 @@ bool QrbPlaybackNode::PublishMessage(
260261
return false;
261262
}
262263

263-
// Publish message<ROSMessageType>
264+
// Publish message<ROSMessageType> using common macros
264265
std::string format = message_buffer_map_.at(pub_index)->message_format;
265266
switch (pub_sub_types_[pub_index]) {
266267
case PubSubType::QrbTransportType:
267268
case PubSubType::DmabufTransportType:
268-
if (format.compare("qrb_ros/transport/type/Image") == 0) {
269-
return publish_message<qrb_ros::transport::type::Image>(pub_index, message_index, header);
270-
} else if (format.compare("qrb_ros/transport/type/Imu") == 0) {
271-
return publish_message<qrb_ros::transport::type::Imu>(pub_index, message_index, header);
272-
} else if (format.compare("dmabuf_transport/type/Image") == 0) {
273-
return publish_message<dmabuf_transport::type::Image>(pub_index, message_index, header);
274-
} else if (format.compare("dmabuf_transport/type/PointCloud2") == 0) {
275-
return publish_message<dmabuf_transport::type::PointCloud2>(
276-
pub_index, message_index, header);
277-
}
269+
#define PUBLISH_TRANSPORT_MESSAGE(format_str, msg_type) \
270+
if (format.compare(format_str) == 0) { \
271+
return publish_message<msg_type>(pub_index, message_index, header); \
272+
}
273+
274+
FOR_EACH_QRB_TRANSPORT_TYPE(PUBLISH_TRANSPORT_MESSAGE)
275+
FOR_EACH_DMABUF_TRANSPORT_TYPE(PUBLISH_TRANSPORT_MESSAGE)
278276
break;
279277
case PubSubType::RosMessaageType:
280278
#define PUBLISH_ROS_MESSAGE(ROSMessageType) \
281-
if (rosidl_generator_traits::name<ROSMessageType>() == format) { \
282-
return publish_message<ROSMessageType>(pub_index, message_index, header); \
283-
} \
284-
285-
PUBLISH_ROS_MESSAGE(sensor_msgs::msg::Image)
286-
PUBLISH_ROS_MESSAGE(sensor_msgs::msg::CompressedImage)
287-
PUBLISH_ROS_MESSAGE(qrb_ros_tensor_list_msgs::msg::TensorList)
279+
if (rosidl_generator_traits::name<ROSMessageType>() == format) { \
280+
return publish_message<ROSMessageType>(pub_index, message_index, header); \
281+
}
282+
283+
FOR_EACH_ROS_MESSAGE_TYPE(PUBLISH_ROS_MESSAGE)
288284
break;
289285
default:
290286
return false;

0 commit comments

Comments
 (0)