Skip to content

Commit f430903

Browse files
committed
linters and license
1 parent 846e72b commit f430903

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

42 files changed

+452
-417
lines changed

.github/CODEOWNERS

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,3 @@
11
# These owners will be the default owners for everything in
22
# the repo. Unless a later match takes precedence.
3-
* @irobot-ros @alsora
3+
* @irobot-ros @alsora @mauropasse

irobot_benchmark/CMakeLists.txt

+5
Original file line numberDiff line numberDiff line change
@@ -39,5 +39,10 @@ install(FILES
3939
${TOPOLOGY_FILES}
4040
DESTINATION lib/${PROJECT_NAME}/topology)
4141

42+
if(BUILD_TESTING)
43+
find_package(ament_lint_auto REQUIRED)
44+
ament_lint_auto_find_test_dependencies()
45+
endif()
46+
4247
ament_package()
4348

irobot_benchmark/benchmark_app_evaluation.py

+11-12
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,13 @@
1-
# Software License Agreement (BSD License)
2-
#
3-
# Copyright (c) 2019, iRobot ROS
4-
# All rights reserved.
5-
#
6-
# This file is part of ros2-performance, which is released under BSD-3-Clause.
7-
# You may use, distribute and modify this code under the BSD-3-Clause license.
8-
#
1+
# Software License Agreement (BSD License)
2+
#
3+
# Copyright (c) 2019, iRobot ROS
4+
# All rights reserved.
5+
#
6+
# This file is part of ros2-performance, which is released under BSD-3-Clause.
7+
# You may use, distribute and modify this code under the BSD-3-Clause license.
8+
#
99

10-
## Create a bar plots.
10+
# Create a bar plots.
1111

1212
import argparse
1313
import matplotlib.pyplot
@@ -17,6 +17,7 @@
1717
import data_utils
1818
import plot_common
1919

20+
2021
def parse_total_latency_csv(file_path):
2122
'''parses a csv into a dictionary structure, given its filepath'''
2223

@@ -71,7 +72,6 @@ def main(argv):
7172
texts.append(label)
7273
units.append(unit)
7374

74-
7575
for key, val in sorted(target_latency.items()):
7676
current_val.append(latency[key])
7777
target_val.append(val)
@@ -80,7 +80,6 @@ def main(argv):
8080
texts.append(label)
8181
units.append(unit)
8282

83-
8483
fig, axs = matplotlib.pyplot.subplots(1, len(current_val), figsize=(11, 3))
8584

8685
for i in range(len(current_val)):
@@ -117,4 +116,4 @@ def main(argv):
117116

118117

119118
if __name__ == '__main__':
120-
main(sys.argv[1:])
119+
main(sys.argv[1:])

irobot_benchmark/package.xml

+8-2
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,12 @@
11
<?xml version="1.0"?>
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3-
<package format="2">
3+
<package format="3">
44
<name>irobot_benchmark</name>
55
<version>0.1.0</version>
66
<description>Benchmark applications to test ros2 performance</description>
77
<maintainer email="[email protected]">Juan Oxoby</maintainer>
8+
<license>BSD 3.0</license>
89
<author>Juan Oxoby</author>
9-
<license>MIT</license>
1010

1111
<buildtool_depend>ament_cmake</buildtool_depend>
1212

@@ -20,6 +20,12 @@
2020
<exec_depend>performance_test</exec_depend>
2121
<exec_depend>performance_test_factory</exec_depend>
2222

23+
<test_depend>ament_lint_auto</test_depend>
24+
<test_depend>ament_cmake_cppcheck</test_depend>
25+
<test_depend>ament_cmake_cpplint</test_depend>
26+
<test_depend>ament_cmake_lint_cmake</test_depend>
27+
<test_depend>ament_cmake_uncrustify</test_depend>
28+
<test_depend>ament_cmake_xmllint</test_depend>
2329

2430
<export>
2531
<build_type>ament_cmake</build_type>

irobot_benchmark/src/irobot_benchmark.cpp

+29-25
Original file line numberDiff line numberDiff line change
@@ -7,15 +7,16 @@
77
* You may use, distribute and modify this code under the BSD-3-Clause license.
88
*/
99

10+
#include <stdlib.h>
11+
#include <sys/wait.h>
12+
1013
#include <vector>
1114
#include <chrono>
1215
#include <iostream>
1316
#include <fstream>
1417
#include <string>
15-
#include <stdlib.h>
16-
#include <sys/wait.h>
1718

18-
#include <rclcpp/rclcpp.hpp>
19+
#include "rclcpp/rclcpp.hpp"
1920

2021
#include "performance_test/communication.hpp"
2122
#include "performance_test/performance_node.hpp"
@@ -30,14 +31,14 @@
3031
using namespace std::chrono_literals;
3132

3233
static void run_test(
33-
int argc, char** argv,
34-
const performance_test::Options &options,
35-
const std::string &topology_json,
36-
pid_t &pid,
37-
const std::string &resources_output_path,
38-
const std::string &events_output_path,
39-
const std::string &latency_all_output_path,
40-
const std::string &latency_total_output_path)
34+
int argc, char ** argv,
35+
const performance_test::Options & options,
36+
const std::string & topology_json,
37+
pid_t & pid,
38+
const std::string & resources_output_path,
39+
const std::string & events_output_path,
40+
const std::string & latency_all_output_path,
41+
const std::string & latency_total_output_path)
4142
{
4243
// Start resources logger
4344
performance_test::ResourceUsageLogger ru_logger(resources_output_path);
@@ -46,12 +47,18 @@ static void run_test(
4647

4748
rclcpp::init(argc, argv);
4849

49-
performance_test::System ros2_system(static_cast<performance_test::ExecutorType>(options.executor));
50+
performance_test::System ros2_system(
51+
static_cast<performance_test::ExecutorType>(options.executor));
5052

5153
// Get the node type from options
5254
auto node_type = static_cast<performance_test::NodeType>(options.node);
5355
// Load topology from json file
54-
auto factory = performance_test::TemplateFactory(options.ipc, options.ros_params, false, "", node_type);
56+
auto factory = performance_test::TemplateFactory(
57+
options.ipc,
58+
options.ros_params,
59+
false,
60+
"",
61+
node_type);
5562

5663
if (options.tracking_options.is_enabled) {
5764
ros2_system.enable_events_logger(events_output_path);
@@ -71,8 +78,7 @@ static void run_test(
7178

7279
ros2_system.print_latency_all_stats();
7380

74-
if (options.topology_json_list.size() > 1)
75-
{
81+
if (options.topology_json_list.size() > 1) {
7682
std::cout << std::endl << "Process total:" << std::endl;
7783
ros2_system.print_latency_total_stats();
7884
}
@@ -82,18 +88,16 @@ static void run_test(
8288
ros2_system.save_latency_total_stats(latency_total_output_path);
8389

8490
// Parent process: wait for children to exit and print system stats
85-
if (pid != 0)
86-
{
87-
if (options.topology_json_list.size() > 1)
88-
{
91+
if (pid != 0) {
92+
if (options.topology_json_list.size() > 1) {
8993
waitpid(getpid() + 1, &pid, 0);
9094
}
9195
std::cout << "System total:" << std::endl;
9296
ros2_system.print_agregate_stats(options.topology_json_list);
9397
}
9498
}
9599

96-
int main(int argc, char** argv)
100+
int main(int argc, char ** argv)
97101
{
98102
auto non_ros_args = rclcpp::remove_ros_arguments(argc, argv);
99103
std::vector<char *> non_ros_args_c_strings;
@@ -103,7 +107,7 @@ int main(int argc, char** argv)
103107
int non_ros_argc = static_cast<int>(non_ros_args_c_strings.size());
104108
auto options = performance_test::Options(non_ros_argc, non_ros_args_c_strings.data());
105109

106-
std::cout<<options<<"\n"<<"Start test!"<<std::endl;
110+
std::cout << options << "\n" << "Start test!" << std::endl;
107111

108112
pid_t pid = getpid();
109113
size_t process_index = performance_test::fork_process(options.topology_json_list.size());
@@ -113,14 +117,14 @@ int main(int argc, char** argv)
113117
// Create results dir based on the topology name
114118
const size_t last_slash = topology_json.find_last_of("/");
115119
std::string topology_basename = topology_json.substr(last_slash + 1, topology_json.length());
116-
std::string dir_name = topology_basename.substr(0,topology_basename.length()-5) + "_log";
120+
std::string dir_name = topology_basename.substr(0, topology_basename.length() - 5) + "_log";
117121

118122
std::string make_dir = "mkdir -p " + dir_name;
119123
const auto ret = system(make_dir.c_str());
120124
static_cast<void>(ret);
121-
std::string resources_output_path = dir_name + "/resources.txt";
122-
std::string events_output_path = dir_name + "/events.txt";
123-
std::string latency_all_output_path = dir_name + "/latency_all.txt";
125+
std::string resources_output_path = dir_name + "/resources.txt";
126+
std::string events_output_path = dir_name + "/events.txt";
127+
std::string latency_all_output_path = dir_name + "/latency_all.txt";
124128
std::string latency_total_output_path = dir_name + "/latency_total.txt";
125129

126130
run_test(

irobot_interfaces_plugin/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
<description>Default plugins for the performance test template factory</description>
77
<maintainer email="[email protected]">Alberto Soragna</maintainer>
88
<author>Alberto Soragna</author>
9-
<license>MIT</license>
9+
<license>BSD 3.0</license>
1010

1111
<buildtool_depend>ament_cmake</buildtool_depend>
1212
<buildtool_depend>rosidl_default_generators</buildtool_depend>

performance_test/include/performance_test/events_logger.hpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,8 @@
1616
#include <chrono>
1717
#include <iomanip>
1818

19-
namespace performance_test {
19+
namespace performance_test
20+
{
2021

2122
/**
2223
* This class implements a synchronous writer for events.
@@ -44,14 +45,14 @@ class EventsLogger
4445

4546
EventsLogger() = delete;
4647

47-
EventsLogger(const std::string& filename);
48+
EventsLogger(const std::string & filename);
4849

4950
void set_start_time(std::chrono::high_resolution_clock::time_point t)
5051
{
5152
_start_time = t;
5253
}
5354

54-
void write_event(const Event& event);
55+
void write_event(const Event & event);
5556

5657
private:
5758
std::chrono::high_resolution_clock::time_point _start_time;

performance_test/include/performance_test/executors.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ enum ExecutorType
3030
STATIC_SINGLE_THREADED_EXECUTOR = 2,
3131
};
3232

33-
inline std::ostream &operator<<(std::ostream &os, const ExecutorType &t)
33+
inline std::ostream & operator<<(std::ostream & os, const ExecutorType & t)
3434
{
3535
std::string executor_name;
3636
switch (t) {

performance_test/include/performance_test/performance_node.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -25,8 +25,8 @@ class PerformanceNode : public NodeT, public PerformanceNodeBase
2525
{
2626
public:
2727
PerformanceNode(
28-
const std::string& name,
29-
const std::string& ros2_namespace = "",
28+
const std::string & name,
29+
const std::string & ros2_namespace = "",
3030
const rclcpp::NodeOptions& node_options = rclcpp::NodeOptions(),
3131
int executor_id = 0)
3232
: NodeT(name, ros2_namespace, node_options), PerformanceNodeBase(executor_id)

0 commit comments

Comments
 (0)