Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Extra options for benchmark #7

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 8 additions & 3 deletions performances/benchmark/src/benchmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,9 @@ int main(int argc, char** argv)
for(const auto& json : json_list) std::cout << json << std::endl;

std::cout << "Intra-process-communication: " << (options.ipc ? "on" : "off") << std::endl;
std::cout << "Parameter service: " << (options.parameter_service ? "on" : "off") << std::endl;
std::cout << "Wait participants discovery: " << (options.wait_pdp ? "on" : "off") << std::endl;
std::cout << "Wait end-points discovery: " << (options.wait_edp ? "on" : "off") << std::endl;
std::cout << "Run test for: " << options.duration_sec << " seconds" << std::endl;
std::cout << "Sampling resources every " << options.resources_sampling_per_ms << "ms" << std::endl;
std::cout << "Start test" << std::endl;
Expand Down Expand Up @@ -85,14 +88,16 @@ int main(int argc, char** argv)
ros2_system.enable_events_logger(events_output_path);

// Load topology from json file
performance_test::TemplateFactory factory = performance_test::TemplateFactory(options.ipc);
performance_test::TemplateFactory factory = performance_test::TemplateFactory(
options.ipc, options.parameter_service);

auto nodes_vec = factory.parse_topology_from_json(topology_json);
ros2_system.add_node(nodes_vec);

// now the system is complete and we can make it spin for the requested duration
bool wait_for_discovery = true;
ros2_system.spin(options.duration_sec, wait_for_discovery);
// bool wait_for_discovery = true;
// ros2_system.spin(options.duration_sec, wait_for_discovery);
ros2_system.spin(options.duration_sec, options.wait_pdp, options.wait_edp);

// terminate the experiment
ru_logger.stop();
Expand Down
31 changes: 31 additions & 0 deletions performances/performance_test/include/cli/options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,9 @@ class Options {
Options()
{
ipc = true;
parameter_service = true;
wait_pdp = true;
wait_edp = true;
duration_sec = 5;
resources_sampling_per_ms = 500;
tracking_options.late_percentage = 20;
Expand All @@ -44,6 +47,10 @@ class Options {
cxxopts::Options options(argv[0], "ROS2 performance benchmark");

std::string ipc_option;
std::string parameter_service_option;
std::string wait_pdp_option;
std::string wait_edp_option;

options.positional_help("FILE [FILE...]").show_positional_help();
options.parse_positional({"topology"});
options.add_options()
Expand All @@ -52,6 +59,12 @@ class Options {
cxxopts::value<std::vector<std::string>>(topology_json_list),"FILE [FILE...]")
("ipc", "intra-process-communication",
cxxopts::value<std::string>(ipc_option)->default_value(ipc ? "on" : "off"),"on/off")
("parameter-server", "Enable/disable creation of parameter server",
cxxopts::value<std::string>(parameter_service_option)->default_value(parameter_service ? "on" : "off"),"on/off")
("wait-pdp", "Enable disable waiting for participants discovery",
cxxopts::value<std::string>(wait_pdp_option)->default_value(parameter_service ? "on" : "off"),"on/off")
("wait-edp", "Enable disable waiting for end-points discovery",
cxxopts::value<std::string>(wait_edp_option)->default_value(parameter_service ? "on" : "off"),"on/off")
("t,time", "test duration", cxxopts::value<int>(duration_sec)->default_value(std::to_string(duration_sec)),"sec")
("s, sampling", "resources sampling period",
cxxopts::value<int>(resources_sampling_per_ms)->default_value(std::to_string(resources_sampling_per_ms)),"msec")
Expand Down Expand Up @@ -81,15 +94,33 @@ class Options {
throw cxxopts::argument_incorrect_type(ipc_option);
}

if (parameter_service_option != "off" && parameter_service_option != "on") {
throw cxxopts::argument_incorrect_type(parameter_service_option);
}

if (wait_pdp_option != "off" && wait_pdp_option != "on") {
throw cxxopts::argument_incorrect_type(wait_pdp_option);
}

if (wait_edp_option != "off" && wait_edp_option != "on") {
throw cxxopts::argument_incorrect_type(wait_edp_option);
}

} catch (const cxxopts::OptionException& e) {
std::cout << "Error parsing options. " << e.what() << std::endl;
exit(1);
}

ipc = (ipc_option == "on" ? true : false);
parameter_service = (parameter_service_option == "on" ? true : false);
wait_pdp = (wait_pdp_option == "on" ? true : false);
wait_edp = (wait_edp_option == "on" ? true : false);
}

bool ipc;
bool parameter_service;
bool wait_pdp;
bool wait_edp;
int duration_sec;
int resources_sampling_per_ms;
std::vector<std::string> topology_json_list;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,8 @@ friend class System;

public:

Node(const std::string& name, const std::string& ros2_namespace = "", bool ipc = true)
: rclcpp::Node(name, ros2_namespace, rclcpp::NodeOptions().use_intra_process_comms(ipc))
Node(const std::string& name, const std::string& ros2_namespace = "", bool ipc = true, bool parameter_service = true)
: rclcpp::Node(name, ros2_namespace, rclcpp::NodeOptions().use_intra_process_comms(ipc).start_parameter_services(parameter_service))
{
RCLCPP_INFO(this->get_logger(), "Node %s created", name.c_str());
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ class System

void add_node(std::shared_ptr<Node> node);

void spin(int duration_sec, bool wait_for_discovery = true);
void spin(int duration_sec, bool wait_pdp_discovery = true, bool wait_edp_discovery = true);

void enable_events_logger(std::string events_logger_path);

Expand All @@ -40,7 +40,7 @@ class System

private:

void wait_discovery();
void wait_discovery(bool wait_pdp = true, bool wait_edp = true);

void wait_pdp_discovery(
std::chrono::milliseconds period = std::chrono::milliseconds(20),
Expand Down
22 changes: 15 additions & 7 deletions performances/performance_test/src/ros2/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ void performance_test::System::add_node(std::shared_ptr<Node> node)
}


void performance_test::System::spin(int duration_sec, bool wait_for_discovery)
void performance_test::System::spin(int duration_sec, bool wait_pdp_discovery, bool wait_edp_discovery)
{
_experiment_duration_sec = duration_sec;
// Store the instant when the experiment started
Expand All @@ -66,10 +66,12 @@ void performance_test::System::spin(int duration_sec, bool wait_for_discovery)
_events_logger->set_start_time(_start_time);
}

if (wait_for_discovery){
// wait until PDP and EDP are finished before starting
// Wait for discovery if needed.
if (wait_pdp_discovery || wait_edp_discovery)
{
// Wait until PDP, EDP, or both are finished before starting
// log events when each is completed
this->wait_discovery();
this->wait_discovery(wait_pdp_discovery, wait_edp_discovery);
}

if (_executor != nullptr){
Expand Down Expand Up @@ -110,16 +112,22 @@ void performance_test::System::spin(int duration_sec, bool wait_for_discovery)
}


void performance_test::System::wait_discovery()
void performance_test::System::wait_discovery(bool wait_pdp, bool wait_edp)
{
// period at which PDP and EDP are checked
std::chrono::milliseconds period = 30ms;
// maximum discovery time, after which the experiment is shut down
std::chrono::milliseconds max_discovery_time = 30s;

wait_pdp_discovery(period, max_discovery_time);
if (wait_pdp)
{
wait_pdp_discovery(period, max_discovery_time);
}

wait_edp_discovery(period, max_discovery_time);
if (wait_edp)
{
wait_edp_discovery(period, max_discovery_time);
}
}


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ int main(int argc, char ** argv)

rclcpp::init(argc, argv);

performance_test::TemplateFactory factory(use_ipc, verbose, ros_namespace);
performance_test::TemplateFactory factory(use_ipc, true, verbose, ros_namespace);
performance_test::System ros2_system(executors);
ros2_system.enable_events_logger(events_file_path);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ int main(int argc, char ** argv)

rclcpp::init(argc, argv);

performance_test::TemplateFactory factory(use_ipc, verbose, ros_namespace);
performance_test::TemplateFactory factory(use_ipc, true, verbose, ros_namespace);
performance_test::System ros2_system(executors);
ros2_system.enable_events_logger(events_file_path);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ int main(int argc, char ** argv)

rclcpp::init(argc, argv);

performance_test::TemplateFactory factory(use_ipc, verbose, ros_namespace);
performance_test::TemplateFactory factory(use_ipc, true, verbose, ros_namespace);
performance_test::System ros2_system(executors);
ros2_system.enable_events_logger(events_file_path);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ int main(int argc, char ** argv)

rclcpp::init(argc, argv);

performance_test::TemplateFactory factory(use_ipc, verbose, ros_namespace);
performance_test::TemplateFactory factory(use_ipc, true, verbose, ros_namespace);
performance_test::System ros2_system(executors);
ros2_system.enable_events_logger(events_file_path);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ int main(int argc, char ** argv)

rclcpp::init(argc, argv);

performance_test::TemplateFactory factory(use_ipc, verbose, ros_namespace);
performance_test::TemplateFactory factory(use_ipc, true, verbose, ros_namespace);
performance_test::System ros2_system(executors);
ros2_system.enable_events_logger(events_file_path);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ int main(int argc, char ** argv)

rclcpp::init(argc, argv);

performance_test::TemplateFactory factory(use_ipc, verbose, ros_namespace);
performance_test::TemplateFactory factory(use_ipc, true, verbose, ros_namespace);
performance_test::System ros2_system(executors);
ros2_system.enable_events_logger(events_file_path);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,9 @@ class TemplateFactory {

public:

TemplateFactory(bool use_ipc = true, bool verbose_mode = false, std::string ros2_namespace = "") :
TemplateFactory(bool use_ipc = true, bool use_parameter_service = true, bool verbose_mode = false, std::string ros2_namespace = "") :
_use_ipc(use_ipc),
_use_parameter_service(use_parameter_service),
_verbose_mode(verbose_mode),
_ros2_namespace(ros2_namespace)
{}
Expand All @@ -38,6 +39,7 @@ class TemplateFactory {
std::shared_ptr<Node> create_node(
std::string name,
bool use_ipc = true,
bool use_parameter_service = true,
bool verbose = false,
std::string ros2_namespace = "");

Expand Down Expand Up @@ -135,6 +137,7 @@ class TemplateFactory {
msg_pass_by_t get_msg_pass_by_from_json(const nlohmann::json entity_json, msg_pass_by_t default_value);

bool _use_ipc;
bool _use_parameter_service;
bool _verbose_mode;
std::string _ros2_namespace;

Expand Down
13 changes: 7 additions & 6 deletions performances/performance_test_factory/src/factory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,11 +24,12 @@ using json = nlohmann::json;
std::shared_ptr<performance_test::Node> performance_test::TemplateFactory::create_node(
std::string name,
bool use_ipc,
bool use_parameter_service,
bool verbose,
std::string ros2_namespace)
{

auto node = std::make_shared<performance_test::Node>(name, ros2_namespace, use_ipc);
auto node = std::make_shared<performance_test::Node>(name, ros2_namespace, use_ipc, use_parameter_service);

if (verbose){
auto ret = rcutils_logging_set_logger_level(node->get_logger().get_name(), RCUTILS_LOG_SEVERITY_DEBUG);
Expand All @@ -53,7 +54,7 @@ std::vector<std::shared_ptr<performance_test::Node>> performance_test::TemplateF
for (int node_id = start_id; node_id < end_id; node_id ++){

std::string node_name = id_to_node_name(node_id);
auto node = this->create_node(node_name, _use_ipc, _verbose_mode, _ros2_namespace);
auto node = this->create_node(node_name, _use_ipc, _use_parameter_service, _verbose_mode, _ros2_namespace);

// TODO: pass publisher list instead of n_publishers, to select the IDs (
// default is a list from 0 to n_pubs or directly from n_subs to n_pubs)
Expand Down Expand Up @@ -86,7 +87,7 @@ std::vector<std::shared_ptr<performance_test::Node>> performance_test::TemplateF
for (int node_id = start_id; node_id < end_id; node_id++){

std::string node_name = id_to_node_name(node_id);
auto node = this->create_node(node_name, _use_ipc, _verbose_mode, _ros2_namespace);
auto node = this->create_node(node_name, _use_ipc, _use_parameter_service, _verbose_mode, _ros2_namespace);

int topic_id = node_id;
std::string topic_name = id_to_topic_name(topic_id);
Expand Down Expand Up @@ -116,7 +117,7 @@ std::vector<std::shared_ptr<performance_test::Node>> performance_test::TemplateF
for (int node_id = start_id; node_id < end_id; node_id++){

std::string node_name = id_to_node_name(node_id);
auto node = this->create_node(node_name, _use_ipc, _verbose_mode, _ros2_namespace);
auto node = this->create_node(node_name, _use_ipc, _use_parameter_service, _verbose_mode, _ros2_namespace);

int period = (1000/frequency);
std::chrono::milliseconds period_ms = std::chrono::milliseconds(period);
Expand Down Expand Up @@ -149,7 +150,7 @@ std::vector<std::shared_ptr<performance_test::Node>> performance_test::TemplateF
for (int node_id = start_id; node_id < end_id; node_id++){

std::string node_name = id_to_node_name(node_id);
auto node = this->create_node(node_name, _use_ipc, _verbose_mode, _ros2_namespace);
auto node = this->create_node(node_name, _use_ipc, _use_parameter_service, _verbose_mode, _ros2_namespace);

int service_id = node_id;
std::string service_name = id_to_service_name(service_id);
Expand Down Expand Up @@ -329,7 +330,7 @@ std::shared_ptr<performance_test::Node> performance_test::TemplateFactory::creat
{

auto node_name = std::string(node_json["node_name"]) + suffix;
auto node = this->create_node(node_name, _use_ipc, _verbose_mode, _ros2_namespace);
auto node = this->create_node(node_name, _use_ipc, _use_parameter_service, _verbose_mode, _ros2_namespace);

return node;
}
Expand Down