Skip to content

Commit 4fd736e

Browse files
wayneparrottMinggang Wang
authored andcommitted
Fix minor benchmark compile & runtime errors due to api changes.
Commit Summary CmakeList.txt 1 - added example_interfaces to find_package() publisher-stress-test.cpp 1 - added qos argument when creating publisher 2 - removed std::make_shared when creating the test message to resolve compilation error. subscription-stress-test.cpp 1 - added missing ';' publisher-stress-test.py 1 - added required QoS argument when creating publisher subscription-stress-test.py 1 - added required QoS argument when creating subscription Fix #739
1 parent 2b75642 commit 4fd736e

File tree

6 files changed

+11
-9
lines changed

6 files changed

+11
-9
lines changed

benchmark/rclcpp/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@ endif()
1313

1414
find_package(ament_cmake REQUIRED)
1515
find_package(rclcpp REQUIRED)
16+
find_package(example_interfaces REQUIRED)
1617
find_package(sensor_msgs REQUIRED)
1718
find_package(std_msgs REQUIRED)
1819
find_package(std_srvs REQUIRED)

benchmark/rclcpp/service/client-stress-test.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ int main(int argc, char* argv[]) {
6161
auto result_future = client->async_send_request(request);
6262
if (rclcpp::spin_until_future_complete(node, result_future) !=
6363
rclcpp::executor::FutureReturnCode::SUCCESS) {
64-
RCLCPP_ERROR(node->get_logger(), "service call failed.")
64+
RCLCPP_ERROR(node->get_logger(), "service call failed.");
6565
return 1;
6666
}
6767
auto result = result_future.get();

benchmark/rclcpp/topic/publisher-stress-test.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -25,8 +25,8 @@
2525
void ShowUsage(const std::string name) {
2626
std::cerr << "Usage: " << name << " [options]\n"
2727
<< "\nOptions:\n"
28-
<< "\n--size [size_kb]\tThe block size\n"
29-
<< "--run <n> \tHow many times to run\n"
28+
<< "\n--size=[size_kb]\tThe block size\n"
29+
<< "--run=<n> \tHow many times to run\n"
3030
<< "--help \toutput usage information"
3131
<< std::endl;
3232
}
@@ -68,9 +68,9 @@ int main(int argc, char* argv[]) {
6868
*height_dim, *width_dim, *channel_dim};
6969
layout->data_offset = 0;
7070

71-
auto msg = std::make_shared<std_msgs::msg::UInt8MultiArray>();
72-
msg->layout = *layout;
73-
msg->data = std::vector<uint8_t>(1024 * amount, 255);
71+
auto msg = std_msgs::msg::UInt8MultiArray();
72+
msg.layout = *layout;
73+
msg.data = std::vector<uint8_t>(1024 * amount, 255);
7474

7575
printf(
7676
"The publisher will publish a UInt8MultiArray topic(contains a size of "
@@ -79,7 +79,7 @@ int main(int argc, char* argv[]) {
7979
auto start = std::chrono::high_resolution_clock::now();
8080
auto node = rclcpp::Node::make_shared("stress_publisher_rclcpp");
8181
auto publisher =
82-
node->create_publisher<std_msgs::msg::UInt8MultiArray>("stress_topic");
82+
node->create_publisher<std_msgs::msg::UInt8MultiArray>("stress_topic", 10);
8383
auto sent_times = 0;
8484

8585
while (rclcpp::ok()) {

benchmark/rclcpp/topic/subscription-stress-test.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@ int main(int argc, char* argv[]) {
2020
auto node = rclcpp::Node::make_shared("stress_subscription_rclcpp");
2121
auto sub = node->create_subscription<std_msgs::msg::UInt8MultiArray>(
2222
"stress_topic",
23+
10,
2324
[](std_msgs::msg::UInt8MultiArray::SharedPtr msg) { (void)msg; });
2425
rclcpp::spin(node);
2526

benchmark/rclpy/topic/publisher-stress-test.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ def main():
5959
print('The publisher will publish a UInt8MultiArray topic(contains a size of %dKB array) %s times.' % (amount, args.run))
6060
start = time()
6161
node = rclpy.create_node('stress_publisher_rclpy')
62-
publisher = node.create_publisher(UInt8MultiArray, 'stress_topic')
62+
publisher = node.create_publisher(UInt8MultiArray, 'stress_topic', 10)
6363
total_times = args.run
6464
sent_times = 0
6565

benchmark/rclpy/topic/subscription-stress-test.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ def callback(msg):
2222
def main():
2323
rclpy.init()
2424
node = rclpy.create_node('stress_subscription_rclpy')
25-
subscription = node.create_subscription(UInt8MultiArray, 'stress_topic', callback)
25+
subscription = node.create_subscription(UInt8MultiArray, 'stress_topic', callback, 10)
2626
while rclpy.ok():
2727
rclpy.spin_once(node)
2828

0 commit comments

Comments
 (0)