Skip to content

Commit

Permalink
Made arguments setable through ros2 launch for scenario_basic_subscri…
Browse files Browse the repository at this point in the history
…ption
CihatAltiparmak committed Jul 20, 2024
1 parent 1bf9e1e commit bc0d06a
Showing 4 changed files with 73 additions and 70 deletions.
17 changes: 2 additions & 15 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -39,27 +39,14 @@ target_include_directories(
target_link_libraries(scenario_perception_pipeline_benchmark_main
PUBLIC "benchmark::benchmark" ${YAML_CPP_LIBRARIES})

install(TARGETS scenario_perception_pipeline_benchmark_main
DESTINATION lib/moveit_middleware_benchmark)

install(DIRECTORY launch config DESTINATION share/moveit_middleware_benchmark)

# ---------------------------------

add_executable(
scenario_basic_subscription_benchmark_main
src/scenario_basic_subscription_benchmark_main.cpp
src/scenarios/scenario_basic_subscription.cpp)

ament_target_dependencies(
scenario_basic_subscription_benchmark_main
PUBLIC
"moveit_ros_planning_interface"
"rclcpp"
"benchmark"
"dynmsg"
"std_msgs"
"yaml-cpp")
scenario_basic_subscription_benchmark_main PUBLIC
"moveit_ros_planning_interface" "rclcpp" "benchmark" "std_msgs")

target_include_directories(
scenario_basic_subscription_benchmark_main
Original file line number Diff line number Diff line change
@@ -34,30 +34,18 @@

/* Author: Cihat Kurtuluş Altıparmak
Description: Benchmarking module to compare the effects of middlewares
against perception pipeline
against topic subscription and publishing
*/

#pragma once

#include <rclcpp/rclcpp.hpp>
#include <benchmark/benchmark.h>
#include <memory>

#include <std_msgs/msg/string.hpp>
#include <dynmsg/msg_parser.hpp>
#include <dynmsg/typesupport.hpp>
#include <dynmsg/yaml_utils.hpp>

#include <ament_index_cpp/get_package_share_directory.hpp>

namespace
{
const std::string PLANNING_GROUP = "panda_arm";
const std::string PACKAGE_SHARE_DIRECTORY = ament_index_cpp::get_package_share_directory("moveit_middleware_benchmark");
const std::string TEST_CASES_YAML_FILE =
PACKAGE_SHARE_DIRECTORY + "/config/scenario_perception_pipeline_test_cases.yaml";
} // namespace

namespace moveit
{
namespace middleware_benchmark
@@ -75,6 +63,8 @@ class ScenarioBasicSubPub
rclcpp::Node::SharedPtr node_;
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
volatile int received_topic_number_;
std::string benchmarked_topic_name_;
int benchmarked_topic_hz_;
};

class ScenarioBasicSubPubFixture : public benchmark::Fixture
84 changes: 52 additions & 32 deletions launch/scenario_basic_subscription_benchmark.launch.py
Original file line number Diff line number Diff line change
@@ -1,40 +1,38 @@
import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, Shutdown
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch.conditions import IfCondition
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from launch.substitutions import LaunchConfiguration
from ament_index_python.packages import get_package_share_directory
from launch.actions import (
DeclareLaunchArgument,
ExecuteProcess,
LogInfo,
RegisterEventHandler,
Shutdown,
OpaqueFunction,
)
from launch.event_handlers import OnProcessExit
from launch_ros.substitutions import FindPackageShare
from launch_ros.actions import Node


def generate_launch_description():
benchmarked_topic_hz = LaunchConfiguration("benchmarked_topic_hz")
benchmarked_topic_hz_arg = DeclareLaunchArgument(
"benchmarked_topic_hz", default_value="1000"
def launch_setup(context, *args, **kwargs):
benchmark_command_args = context.perform_substitution(
LaunchConfiguration("benchmark_command_args")
).split()

benchmarked_topic_hz = int(
context.perform_substitution(LaunchConfiguration("benchmarked_topic_hz"))
)

benchmarked_topic_name = LaunchConfiguration("bencmarked_topic_name")
benchmarked_topic_name_arg = DeclareLaunchArgument(
"bencmarked_topic_name", default_value="/benchmarked_topic1"
benchmarked_topic_name = context.perform_substitution(
LaunchConfiguration("benchmarked_topic_name")
)

max_receiving_topic_number = int(
context.perform_substitution(LaunchConfiguration("max_receiving_topic_number"))
)

topic_publisher = ExecuteProcess(
cmd=[
[
f"ros2 topic pub -r ",
benchmarked_topic_hz,
" ",
benchmarked_topic_name,
" std_msgs/msg/String ",
'"data : 1"',
f"ros2 topic pub -r {benchmarked_topic_hz} {benchmarked_topic_name} std_msgs/msg/String 'data : 1'",
]
],
shell=True,
@@ -45,21 +43,43 @@ def generate_launch_description():
package="moveit_middleware_benchmark",
executable="scenario_basic_subscription_benchmark_main",
output="both",
arguments=[
"--benchmark_out=middleware_benchmark_results.json",
"--benchmark_out_format=json",
],
arguments=benchmark_command_args,
parameters=[
{"max_receiving_topic_number": 100000},
{"max_receiving_topic_number": max_receiving_topic_number},
{"benchmarked_topic_name": benchmarked_topic_name},
{"benchmarked_topic_hz": benchmarked_topic_hz},
],
on_exit=Shutdown(),
)

return [topic_publisher, benchmark_main_node]


def generate_launch_description():
declared_arguments = []

benchmark_command_args = DeclareLaunchArgument(
"benchmark_command_args",
default_value="--benchmark_out=middleware_benchmark_results.json --benchmark_out_format=json --benchmark_repetitions=6",
description="Google Benchmark Tool Arguments",
)
declared_arguments.append(benchmark_command_args)

benchmarked_topic_hz_arg = DeclareLaunchArgument(
"benchmarked_topic_hz", default_value="10000"
)
declared_arguments.append(benchmarked_topic_hz_arg)

benchmarked_topic_name_arg = DeclareLaunchArgument(
"benchmarked_topic_name", default_value="/benchmarked_topic1"
)
declared_arguments.append(benchmarked_topic_name_arg)

max_receiving_topic_number_arg = DeclareLaunchArgument(
"max_receiving_topic_number", default_value="1000000"
)
declared_arguments.append(max_receiving_topic_number_arg)

return LaunchDescription(
[
benchmarked_topic_hz_arg,
benchmarked_topic_name_arg,
topic_publisher,
benchmark_main_node,
]
declared_arguments + [OpaqueFunction(function=launch_setup)]
)
26 changes: 16 additions & 10 deletions src/scenarios/scenario_basic_subscription.cpp
Original file line number Diff line number Diff line change
@@ -34,7 +34,7 @@

/* Author: Cihat Kurtuluş Altıparmak
Description: Benchmarking module to compare the effects of middlewares
against perception pipeline
against topic subscription and publishing
*/

#include "moveit_middleware_benchmark/scenarios/scenario_basic_subscription.hpp"
@@ -46,20 +46,27 @@ namespace middleware_benchmark

ScenarioBasicSubPub::ScenarioBasicSubPub(rclcpp::Node::SharedPtr node) : node_(node)
{
sub_ = node_->create_subscription<std_msgs::msg::String>(
"/benchmarked_topic1", 10, std::bind(&ScenarioBasicSubPub::subCallback, this, std::placeholders::_1));
received_topic_number_ = 0;
node_->get_parameter("benchmarked_topic_name", benchmarked_topic_name_);
node_->get_parameter("benchmarked_topic_hz", benchmarked_topic_hz_);
}

void ScenarioBasicSubPub::runTestCase(const int& max_received_topic_number)
{
rclcpp::Rate rate(10);
RCLCPP_INFO(node_->get_logger(), "Subscribing to topic : %s with hz %d", benchmarked_topic_name_.c_str(),
benchmarked_topic_hz_);

while (received_topic_number_ < max_received_topic_number)
{
// RCLCPP_INFO(node_->get_logger(), "deneme %d %d", received_topic_number_, max_received_topic_number);
}
RCLCPP_INFO(node_->get_logger(), "Im out!");
sub_ = node_->create_subscription<std_msgs::msg::String>(
benchmarked_topic_name_, 10, std::bind(&ScenarioBasicSubPub::subCallback, this, std::placeholders::_1));

RCLCPP_INFO(node_->get_logger(),
"Successfully subscribed to topic %s with hz %d! When received msg number is bigger than %d, benchmark "
"will be finished!",
benchmarked_topic_name_.c_str(), benchmarked_topic_hz_, max_received_topic_number);

while (received_topic_number_ < max_received_topic_number) {}

RCLCPP_INFO(node_->get_logger(), "Benchmarked test case is finished!");
}

void ScenarioBasicSubPub::subCallback(std_msgs::msg::String::SharedPtr msg)
@@ -78,7 +85,6 @@ void ScenarioBasicSubPubFixture::SetUp(::benchmark::State& /*state*/)
node_ = std::make_shared<rclcpp::Node>("test_scenario_basic_sub_pub",
rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true));

// max_receiving_topic_number_ = 1000;
node_->get_parameter("max_receiving_topic_number", max_receiving_topic_number_);

executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

0 comments on commit bc0d06a

Please sign in to comment.