From 915bc4dbfac53dd444acc29fa6a537d859eeb9cc Mon Sep 17 00:00:00 2001 From: Pablo Date: Tue, 19 Oct 2021 02:42:32 -0700 Subject: [PATCH 01/11] WIP --- autoware_reference_system/CMakeLists.txt | 14 ++++-- autoware_reference_system/package.xml | 1 + ...toware_default_klepsydrasinglethreaded.cpp | 46 +++++++++++++++++++ 3 files changed, 57 insertions(+), 4 deletions(-) create mode 100644 autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp diff --git a/autoware_reference_system/CMakeLists.txt b/autoware_reference_system/CMakeLists.txt index c3fe4596..9674ed31 100644 --- a/autoware_reference_system/CMakeLists.txt +++ b/autoware_reference_system/CMakeLists.txt @@ -41,6 +41,10 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() +find_package(kpsr_ros2_executor REQUIRED) +find_package(Klepsydra REQUIRED) +find_package(KlepsydraAdmin REQUIRED) + find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() @@ -65,9 +69,11 @@ ament_auto_add_executable(number_cruncher_benchmark ) # Add new executors to test here -#ament_auto_add_executable(autoware_default_custom -# src/ros2/executor/autoware_default_custom.cpp -#) +ament_auto_add_executable(autoware_default_custom + src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp +) + +ament_target_dependencies(autoware_default_custom ${dependencies}) if(${BUILD_TESTING}) find_package(ament_lint_auto REQUIRED) @@ -103,7 +109,7 @@ if(${BUILD_TESTING}) autoware_default_singlethreaded autoware_default_staticsinglethreaded autoware_default_multithreaded - #autoware_default_custom + autoware_default_custom ) # Add more run times here (time to run traces for) diff --git a/autoware_reference_system/package.xml b/autoware_reference_system/package.xml index e300278c..2a6757b7 100644 --- a/autoware_reference_system/package.xml +++ b/autoware_reference_system/package.xml @@ -17,6 +17,7 @@ rclcpp reference_interfaces rcl_interfaces + kpsr_ros2_executor ament_cmake_pytest ament_cmake_gtest diff --git a/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp b/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp new file mode 100644 index 00000000..7489420d --- /dev/null +++ b/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp @@ -0,0 +1,46 @@ +// Copyright 2021 Apex.AI, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "rclcpp/rclcpp.hpp" + +#include "reference_system/system/systems.hpp" + +#include "autoware_reference_system/autoware_system_builder.hpp" +#include "autoware_reference_system/system/timing/benchmark.hpp" +#include "autoware_reference_system/system/timing/default.hpp" + +#include + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + + using TimeConfig = nodes::timing::Default; + // uncomment for benchmarking + // using TimeConfig = nodes::timing::BenchmarkCPUUsage; + // set_benchmark_mode(true); + + auto nodes = create_autoware_nodes(); + + rclcpp::Executor::SharedPtr executor = kpsr::ros2::ExecutorFactory::createExecutor(kpsr::ros2::QueueSize::_256, false); + for (auto & node : nodes) { + executor->add_node(node); + } + executor->spin(); + + nodes.clear(); + rclcpp::shutdown(); + + return 0; +} From 26450dcd99b356a0da7d15416ca195739e3b45f1 Mon Sep 17 00:00:00 2001 From: paulagb8894 Date: Tue, 11 Oct 2022 14:45:15 +0200 Subject: [PATCH 02/11] updated kpsr executor --- autoware_reference_system/CMakeLists.txt | 1 + ...toware_default_klepsydrasinglethreaded.cpp | 30 +++++++++++++++++-- 2 files changed, 29 insertions(+), 2 deletions(-) diff --git a/autoware_reference_system/CMakeLists.txt b/autoware_reference_system/CMakeLists.txt index 9674ed31..cc6fe892 100644 --- a/autoware_reference_system/CMakeLists.txt +++ b/autoware_reference_system/CMakeLists.txt @@ -44,6 +44,7 @@ endif() find_package(kpsr_ros2_executor REQUIRED) find_package(Klepsydra REQUIRED) find_package(KlepsydraAdmin REQUIRED) +find_package(KlepsydraStreaming REQUIRED) find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() diff --git a/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp b/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp index 7489420d..f29b97cc 100644 --- a/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp +++ b/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp @@ -13,7 +13,7 @@ // limitations under the License. #include "rclcpp/rclcpp.hpp" - +#include #include "reference_system/system/systems.hpp" #include "autoware_reference_system/autoware_system_builder.hpp" @@ -33,7 +33,33 @@ int main(int argc, char * argv[]) auto nodes = create_autoware_nodes(); - rclcpp::Executor::SharedPtr executor = kpsr::ros2::ExecutorFactory::createExecutor(kpsr::ros2::QueueSize::_256, false); + kpsr::mem::MemEnv environment; + environment.setPropertyString("container_name", "eventLoop_systemRef"); + environment.setPropertyString("admin_log_filename", ""); + environment.setPropertyString("stat_filename", "/home/kpsruser/development/ros2/ros2_ref_system/ros_ref.csv"); + environment.setPropertyString("streaming_conf_file", "/home/kpsruser/development/ros2/ros2_ref_system/outputPolicy.json"); + environment.setPropertyString("log_filename", "/home/kpsruser/development/ros2/ros2_ref_system/ros_ref.log"); + + environment.setPropertyInt("log_level", 2); + environment.setPropertyInt("pool_size", 100); + environment.setPropertyInt("number_of_cores", 11); + environment.setPropertyInt("critical_thread_pool_size", 16); + environment.setPropertyInt("non_critical_thread_pool_size", 1); + environment.setPropertyInt("number_of_parallel_threads", 0); + environment.setPropertyInt("stat_log_interval_ms", 1000); + environment.setPropertyInt("admin_log_interval", 1000); + + environment.setPropertyBool("to_std_out", true); + environment.setPropertyBool("log_to_file", true); + environment.setPropertyBool("admin_log_to_file", false); + environment.setPropertyBool("stat_socket_container_enable", false); + environment.setPropertyBool("stat_file_container_enable", true); + environment.setPropertyBool("use_default_streaming_factory", true); + environment.setPropertyBool("test_dnn", false); + environment.setPropertyBool("export_streaming_configuration", true); + + rclcpp::Executor::SharedPtr executor = kpsr::ros2::ExecutorFactory::createExecutor(&environment); + for (auto & node : nodes) { executor->add_node(node); } From 44cff9576f03776026b1d8b77765d0985a028c09 Mon Sep 17 00:00:00 2001 From: paulagb8894 Date: Wed, 4 Jan 2023 17:56:18 +0100 Subject: [PATCH 03/11] temporary changes --- ...toware_default_klepsydrasinglethreaded.cpp | 30 +++++++++++++++---- .../reference_system/nodes/rclcpp/command.hpp | 4 ++- .../reference_system/nodes/rclcpp/cyclic.hpp | 2 ++ .../reference_system/nodes/rclcpp/fusion.hpp | 2 ++ .../nodes/rclcpp/intersection.hpp | 1 + .../reference_system/nodes/rclcpp/sensor.hpp | 1 + .../nodes/rclcpp/transform.hpp | 1 + 7 files changed, 35 insertions(+), 6 deletions(-) diff --git a/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp b/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp index f29b97cc..793edfd9 100644 --- a/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp +++ b/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp @@ -34,15 +34,16 @@ int main(int argc, char * argv[]) auto nodes = create_autoware_nodes(); kpsr::mem::MemEnv environment; + /* environment.setPropertyString("container_name", "eventLoop_systemRef"); environment.setPropertyString("admin_log_filename", ""); - environment.setPropertyString("stat_filename", "/home/kpsruser/development/ros2/ros2_ref_system/ros_ref.csv"); - environment.setPropertyString("streaming_conf_file", "/home/kpsruser/development/ros2/ros2_ref_system/outputPolicy.json"); - environment.setPropertyString("log_filename", "/home/kpsruser/development/ros2/ros2_ref_system/ros_ref.log"); + environment.setPropertyString("stat_filename", "/home/ubuntu/development/ros2/ref_results/ros_ref.csv"); + environment.setPropertyString("streaming_conf_file", "/home/ubuntu/development/ros2/ref_results/outputPolicy.json"); + environment.setPropertyString("log_filename", "/home/ubuntu/development/ros2/ref_results/ros_ref.log"); environment.setPropertyInt("log_level", 2); environment.setPropertyInt("pool_size", 100); - environment.setPropertyInt("number_of_cores", 11); + environment.setPropertyInt("number_of_cores", 3); environment.setPropertyInt("critical_thread_pool_size", 16); environment.setPropertyInt("non_critical_thread_pool_size", 1); environment.setPropertyInt("number_of_parallel_threads", 0); @@ -57,9 +58,28 @@ int main(int argc, char * argv[]) environment.setPropertyBool("use_default_streaming_factory", true); environment.setPropertyBool("test_dnn", false); environment.setPropertyBool("export_streaming_configuration", true); + */ + environment.setPropertyString("log_filename", ""); + environment.setPropertyInt("log_level", 2); + environment.setPropertyInt("pool_size", 1); + environment.setPropertyInt("number_of_cores", 4);//1,2,3,4 + environment.setPropertyInt("number_of_trypost", 0); + environment.setPropertyInt("critical_thread_pool_size", 32); + environment.setPropertyInt("non_critical_thread_pool_size", 32); + environment.setPropertyInt("number_of_parallel_threads", 0); + + // + environment.setPropertyInt("stat_log_interval_ms", 1000); + environment.setPropertyBool("stat_file_container_enable", false); + environment.setPropertyString("stat_filename", "/home/ubuntu/development/ros2/ros2_core_ws/stats/benchmarks_internal_sub.csv"); + // + environment.setPropertyString("streaming_conf_file", "/home/ubuntu/development/ros2/ros2_core_ws/stats/policy.json"); + environment.setPropertyBool("use_default_streaming_factory", false); + environment.setPropertyBool("test_dnn", false); + environment.setPropertyBool("export_streaming_configuration", false); rclcpp::Executor::SharedPtr executor = kpsr::ros2::ExecutorFactory::createExecutor(&environment); - + for (auto & node : nodes) { executor->add_node(node); } diff --git a/reference_system/include/reference_system/nodes/rclcpp/command.hpp b/reference_system/include/reference_system/nodes/rclcpp/command.hpp index 2f2924fe..603fdc13 100644 --- a/reference_system/include/reference_system/nodes/rclcpp/command.hpp +++ b/reference_system/include/reference_system/nodes/rclcpp/command.hpp @@ -40,9 +40,11 @@ class Command : public rclcpp::Node private: void input_callback(const message_t::SharedPtr input_message) - { + { + uint64_t timestamp = now_as_int(); uint32_t missed_samples = get_missed_samples_and_update_seq_nr(input_message, sequence_number_); print_sample_path(this->get_name(), missed_samples, input_message); + //std::cout << "[KPSR] " << get_name() << " " << timestamp << " " << now_as_int() << std::endl; } private: diff --git a/reference_system/include/reference_system/nodes/rclcpp/cyclic.hpp b/reference_system/include/reference_system/nodes/rclcpp/cyclic.hpp index bed96a7d..f209b720 100644 --- a/reference_system/include/reference_system/nodes/rclcpp/cyclic.hpp +++ b/reference_system/include/reference_system/nodes/rclcpp/cyclic.hpp @@ -84,6 +84,8 @@ class Cyclic : public rclcpp::Node output_message.get().data[0] = number_cruncher_result; publisher_->publish(std::move(output_message)); + + //std::cout << "[KPSR] " << get_name() << " " << timestamp << " " << now_as_int() << std::endl; } private: diff --git a/reference_system/include/reference_system/nodes/rclcpp/fusion.hpp b/reference_system/include/reference_system/nodes/rclcpp/fusion.hpp index d7989976..4f4efbc1 100644 --- a/reference_system/include/reference_system/nodes/rclcpp/fusion.hpp +++ b/reference_system/include/reference_system/nodes/rclcpp/fusion.hpp @@ -83,6 +83,8 @@ class Fusion : public rclcpp::Node subscriptions_[0].cache.reset(); subscriptions_[1].cache.reset(); + + //std::cout << "[KPSR] " << get_name() << " " << timestamp << " " << now_as_int() << std::endl; } private: diff --git a/reference_system/include/reference_system/nodes/rclcpp/intersection.hpp b/reference_system/include/reference_system/nodes/rclcpp/intersection.hpp index 630673e3..dd19aac9 100644 --- a/reference_system/include/reference_system/nodes/rclcpp/intersection.hpp +++ b/reference_system/include/reference_system/nodes/rclcpp/intersection.hpp @@ -70,6 +70,7 @@ class Intersection : public rclcpp::Node // use result so that it is not optimizied away by some clever compiler output_message.get().data[0] = number_cruncher_result; connections_[id].publisher->publish(std::move(output_message)); + //std::cout << "[KPSR] " << get_name() << " " << timestamp << " " << now_as_int() << std::endl; } private: diff --git a/reference_system/include/reference_system/nodes/rclcpp/sensor.hpp b/reference_system/include/reference_system/nodes/rclcpp/sensor.hpp index 7927aab7..1fc7bb26 100644 --- a/reference_system/include/reference_system/nodes/rclcpp/sensor.hpp +++ b/reference_system/include/reference_system/nodes/rclcpp/sensor.hpp @@ -49,6 +49,7 @@ class Sensor : public rclcpp::Node set_sample(this->get_name(), sequence_number_++, 0, timestamp, message.get()); publisher_->publish(std::move(message)); + //std::cout << "[KPSR] " << get_name() << " " << timestamp << " " << now_as_int() << std::endl; } private: diff --git a/reference_system/include/reference_system/nodes/rclcpp/transform.hpp b/reference_system/include/reference_system/nodes/rclcpp/transform.hpp index 9fc02fe5..acb5d109 100644 --- a/reference_system/include/reference_system/nodes/rclcpp/transform.hpp +++ b/reference_system/include/reference_system/nodes/rclcpp/transform.hpp @@ -62,6 +62,7 @@ class Transform : public rclcpp::Node // use result so that it is not optimizied away by some clever compiler output_message.get().data[0] = number_cruncher_result; publisher_->publish(std::move(output_message)); + //std::cout << "[KPSR] " << get_name() << " " << timestamp << " " << now_as_int() << std::endl; } private: From e9cf43b8a5d1365824dedfd782476023924845e7 Mon Sep 17 00:00:00 2001 From: Guillermo Sarabia Date: Fri, 13 Jan 2023 13:46:45 +0100 Subject: [PATCH 04/11] Update reference system --- .../autoware_default_klepsydrasinglethreaded.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp b/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp index 793edfd9..ff8a2c5c 100644 --- a/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp +++ b/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp @@ -14,13 +14,13 @@ #include "rclcpp/rclcpp.hpp" #include -#include "reference_system/system/systems.hpp" +#include "reference_system/system/type/rclcpp_system.hpp" #include "autoware_reference_system/autoware_system_builder.hpp" #include "autoware_reference_system/system/timing/benchmark.hpp" #include "autoware_reference_system/system/timing/default.hpp" -#include +#include int main(int argc, char * argv[]) { @@ -71,14 +71,14 @@ int main(int argc, char * argv[]) // environment.setPropertyInt("stat_log_interval_ms", 1000); environment.setPropertyBool("stat_file_container_enable", false); - environment.setPropertyString("stat_filename", "/home/ubuntu/development/ros2/ros2_core_ws/stats/benchmarks_internal_sub.csv"); + environment.setPropertyString("stat_filename", "/home/ubuntu/development/klepsydra/reference_system/stats/benchmarks_internal_sub.csv"); // - environment.setPropertyString("streaming_conf_file", "/home/ubuntu/development/ros2/ros2_core_ws/stats/policy.json"); + environment.setPropertyString("streaming_conf_file", "/home/ubuntu/development/klepsydra/reference_system/policy.json"); environment.setPropertyBool("use_default_streaming_factory", false); environment.setPropertyBool("test_dnn", false); environment.setPropertyBool("export_streaming_configuration", false); - rclcpp::Executor::SharedPtr executor = kpsr::ros2::ExecutorFactory::createExecutor(&environment); + rclcpp::Executor::SharedPtr executor = kpsr::ros2::StreamingExecutorFactory::createExecutor(&environment); for (auto & node : nodes) { executor->add_node(node); From 6841ac517c582a246a5f19e097895c1ba6d07e8e Mon Sep 17 00:00:00 2001 From: Guillermo Sarabia Date: Tue, 31 Jan 2023 17:06:22 +0000 Subject: [PATCH 05/11] genetic algo --- ...toware_default_klepsydrasinglethreaded.cpp | 2 +- genetic_algo/genetic_algorithm.py | 161 ++++++++++++++++++ .../requirements.txt | 1 + 3 files changed, 163 insertions(+), 1 deletion(-) create mode 100644 genetic_algo/genetic_algorithm.py rename requirements.txt => genetic_algo/requirements.txt (81%) diff --git a/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp b/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp index ff8a2c5c..787f1899 100644 --- a/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp +++ b/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp @@ -60,7 +60,7 @@ int main(int argc, char * argv[]) environment.setPropertyBool("export_streaming_configuration", true); */ environment.setPropertyString("log_filename", ""); - environment.setPropertyInt("log_level", 2); + environment.setPropertyInt("log_level", 6); environment.setPropertyInt("pool_size", 1); environment.setPropertyInt("number_of_cores", 4);//1,2,3,4 environment.setPropertyInt("number_of_trypost", 0); diff --git a/genetic_algo/genetic_algorithm.py b/genetic_algo/genetic_algorithm.py new file mode 100644 index 00000000..c4e0cb39 --- /dev/null +++ b/genetic_algo/genetic_algorithm.py @@ -0,0 +1,161 @@ +import json +import shutil +import tempfile + +import pygad +import pandas as pd +import numpy as np +from reference_system_py.benchmark import get_benchmark_directories_below, generate_trace +from reference_system_py.std_latency import parseLogSummaryFromFiles + +n_number_cruncher = 4096 +with open('policy_ref_def.json') as f: + policy_template = json.load(f) + +edges = [('FrontLidarDriver', 'PointsTransformerFront'), +('RearLidarDriver', 'PointsTransformerRear'), +('PointCloudFusion', 'VoxelGridDownsampler'), +('PointCloudMap', 'PointCloudMapLoader'), +('PointCloudFusion', 'RayGroundFilter'), +('EuclideanClusterDetector', 'ObjectCollisionEstimator'), +('BehaviorPlanner', 'MPCController'), +('Lanelet2MapLoader', 'ParkingPlanner'), +('Lanelet2MapLoader', 'LanePlanner'), +('PointsTransformerFront', 'PointCloudFusion'), +('VoxelGridDownsampler', 'NDTLocalizer'), +('MPCController', 'VehicleInterface'), +('Visualizer', 'Lanelet2GlobalPlanner'), +('Lanelet2Map', 'Lanelet2MapLoader'), +('ObjectCollisionEstimator', 'BehaviorPlanner'), +('RayGroundFilter', 'EuclideanClusterDetector'), +('VehicleInterface', 'VehicleDBWSystem'), +('EuclideanIntersection', 'IntersectionOutput'), +('PointsTransformerRear', 'PointCloudFusion'), +('PointCloudMapLoader', 'NDTLocalizer'), +('BehaviorPlanner', 'VehicleInterface'), +('NDTLocalizer', 'Lanelet2GlobalPlanner'), +('Lanelet2GlobalPlanner', 'Lanelet2MapLoader'), +('NDTLocalizer', 'BehaviorPlanner'), +('EuclideanClusterSettings', 'EuclideanClusterDetector'), +('Lanelet2GlobalPlanner', 'BehaviorPlanner'), +('ParkingPlanner', 'BehaviorPlanner'), +('LanePlanner', 'BehaviorPlanner'), +('Lanelet2MapLoader', 'BehaviorPlanner')] + +hot_path_nodes = ["FrontLidarDriver", + "PointsTransformerFront", + "RearLidarDriver", + "PointsTransformerRear", + "PointCloudFusion", + "RayGroundFilter", + "EuclideanClusterDetector", + "ObjectCollisionEstimator"] + +other_nodes = ["PointCloudMap", + "Visualizer", + "Lanelet2Map", + "EuclideanClusterSettings", + "PointCloudMapLoader", + "MPCController", + "VehicleInterface", + "VehicleDBWSystem", + "NDTLocalizer", + "Lanelet2GlobalPlanner", + "Lanelet2MapLoader", + "ParkingPlanner", + "LanePlanner", + "IntersectionOutput", + "VoxelGridDownsampler"] + + +def fitness_func(solution, idx_sol): + print(idx_sol) + update_policy(solution) + + latency_hot_path = calculate_latency_policy() + + return -latency_hot_path + + +def update_policy(solution): + base_policy = policy_template.copy() + node_dicts = dict(zip(hot_path_nodes + other_nodes, solution)) + for composite_node in base_policy['layer_event_loop_map'].keys(): + node = composite_node.split('$')[0] + if node in node_dicts: + base_policy['layer_event_loop_map'][composite_node]['coreId'] = int(node_dicts[node]) + # Execute. + with open('/home/ubuntu/development/klepsydra/reference_system/policy.json', 'w', encoding='utf-8') as f: + json.dump(base_policy, f, ensure_ascii=False, indent=4) + + +def calculate_latency_policy(): + trace_type = 'std' + exe = 'autoware_default_custom' + rmw = 'rmw_cyclonedds_cpp' + runtime = 30 + try: + with tempfile.TemporaryDirectory() as temp_dir_name: + common_args = {'pkg': 'autoware_reference_system', + 'directory': temp_dir_name} + + generate_trace(trace_type, exe, rmw=rmw, runtime_sec=runtime, **common_args) + + trace_dirs = get_benchmark_directories_below(common_args['directory'], runtime_sec=runtime) + + data, hot_path_name = parseLogSummaryFromFiles( + [directory + '/std_output.log' for directory in trace_dirs], runtime) + latency_hot_path = data[(exe, rmw)]['hot_path']['latency'][-1]['mean'] + print(latency_hot_path) + except: + latency_hot_path = 100000 + return latency_hot_path + + +fitness_function = fitness_func +num_generations = 10 +num_parents_mating = 4 + +gene_type = np.int32 +sol_per_pop = 8 +num_genes = len(hot_path_nodes) + len(other_nodes) + +init_range_low = 0 +init_range_high = 3 + +parent_selection_type = "sss" +keep_parents = 1 + +crossover_type = "single_point" + +mutation_type = "random" +mutation_percent_genes = 15 + +ga_instance = pygad.GA(num_generations=num_generations, + num_parents_mating=num_parents_mating, + fitness_func=fitness_function, + sol_per_pop=sol_per_pop, + num_genes=num_genes, + gene_type=gene_type, + init_range_low=init_range_low, + init_range_high=init_range_high, + parent_selection_type=parent_selection_type, + keep_parents=keep_parents, + crossover_type=crossover_type, + mutation_type=mutation_type, + mutation_percent_genes=mutation_percent_genes) + +#ga_instance.run() + +filename = f'genetic_{n_number_cruncher}' +ga_instance.save(filename=filename) +#pygad.load(filename=filename) +solution, solution_fitness, solution_idx = ga_instance.best_solution() +update_policy(solution) + +src = '/home/ubuntu/development/klepsydra/reference_system/policy.json' +dst = f'/home/ubuntu/development/klepsydra/reference_system/policy_{n_number_cruncher}.json' +shutil.copyfile(src, dst) + + +print(solution_fitness) \ No newline at end of file diff --git a/requirements.txt b/genetic_algo/requirements.txt similarity index 81% rename from requirements.txt rename to genetic_algo/requirements.txt index be29a158..0f3c1669 100644 --- a/requirements.txt +++ b/genetic_algo/requirements.txt @@ -1,2 +1,3 @@ bokeh==2.4.1 psrecord==1.2 +pygad From 80a8038fed27bc6586c039acb7cbdf5fdadb6a3c Mon Sep 17 00:00:00 2001 From: paulagb8894 Date: Wed, 4 Jan 2023 17:56:18 +0100 Subject: [PATCH 06/11] removing environment --- .gitignore | 2 + autoware_reference_system/CMakeLists.txt | 11 + .../src/ros2/common/config.h.in | 1 + .../src/ros2/data/streaming_conf.json.in | 26 ++ .../src/ros2/data/streaming_policy.json | 289 ++++++++++++++++++ ...toware_default_klepsydrasinglethreaded.cpp | 50 +-- 6 files changed, 332 insertions(+), 47 deletions(-) create mode 100644 autoware_reference_system/src/ros2/common/config.h.in create mode 100644 autoware_reference_system/src/ros2/data/streaming_conf.json.in create mode 100644 autoware_reference_system/src/ros2/data/streaming_policy.json diff --git a/.gitignore b/.gitignore index 9a537a02..260c3377 100644 --- a/.gitignore +++ b/.gitignore @@ -8,3 +8,5 @@ doxybook2** bin include lib +**/**/**/**/config.h +**/**/**/**/streaming_conf.json diff --git a/autoware_reference_system/CMakeLists.txt b/autoware_reference_system/CMakeLists.txt index 65c50482..ceb6e1a7 100644 --- a/autoware_reference_system/CMakeLists.txt +++ b/autoware_reference_system/CMakeLists.txt @@ -67,7 +67,18 @@ add_benchmark_executable(autoware_default_custom src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp ) +set(CONF_DATA ${CMAKE_CURRENT_SOURCE_DIR}/src/ros2/data) +#Configure modules header with variables configured +configure_file("${CMAKE_CURRENT_SOURCE_DIR}/src/ros2/common/config.h.in" + "${CMAKE_CURRENT_SOURCE_DIR}/src/ros2/common/config.h") +configure_file("${CMAKE_CURRENT_SOURCE_DIR}/src/ros2/data/streaming_conf.json.in" + "${CMAKE_CURRENT_SOURCE_DIR}/src/ros2/data/streaming_conf.json") + +target_include_directories( + autoware_default_custom PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/src/ros2/common) + +ament_export_include_directories(autoware_default_custom PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/src/ros2/common) ament_target_dependencies(autoware_default_custom ${dependencies}) if(${BUILD_TESTING}) diff --git a/autoware_reference_system/src/ros2/common/config.h.in b/autoware_reference_system/src/ros2/common/config.h.in new file mode 100644 index 00000000..7a4ffd73 --- /dev/null +++ b/autoware_reference_system/src/ros2/common/config.h.in @@ -0,0 +1 @@ +#cmakedefine CONF_DATA "@CONF_DATA@" \ No newline at end of file diff --git a/autoware_reference_system/src/ros2/data/streaming_conf.json.in b/autoware_reference_system/src/ros2/data/streaming_conf.json.in new file mode 100644 index 00000000..44562a5e --- /dev/null +++ b/autoware_reference_system/src/ros2/data/streaming_conf.json.in @@ -0,0 +1,26 @@ +{ + "StringProperties": { + "container_name": "test", + "log_filename": "", + "streaming_conf_file":"@CONF_DATA@/streaming_policy.json", + "processor_intensive_layers": "max" + }, + "BoolProperties": { + "test_dnn": false, + "stat_socket_container_enable": false, + "stat_file_container_enable": false, + "use_default_streaming_factory": false + }, + "IntProperties": { + "stat_log_interval_ms": 1000, + "pool_size": 1, + "stat_admin_port": 9595, + "stat_system_port": 9696, + "log_level": 0, + "number_of_event_loops": 4, + "number_of_cores": 4, + "critical_thread_pool_size": 32, + "non_critical_thread_pool_size": 32, + "number_of_parallel_threads": 1 + } +} \ No newline at end of file diff --git a/autoware_reference_system/src/ros2/data/streaming_policy.json b/autoware_reference_system/src/ros2/data/streaming_policy.json new file mode 100644 index 00000000..1356ab6d --- /dev/null +++ b/autoware_reference_system/src/ros2/data/streaming_policy.json @@ -0,0 +1,289 @@ +{ + "pool_size": 1, + "number_of_cores": 4, + "number_of_event_loops": 4, + "number_of_parallel_threads": 1, + "non_critical_thread_pool_size": 32, + "event_loop_core_map": { + "0": [ + 0 + ], + "1": [ + 1 + ], + "2": [ + 2 + ], + "3": [ + 3 + ] + }, + "layer_event_loop_map": { + "BehaviorPlanner$ObjectCollisionEstimator": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "BehaviorPlanner$NDTLocalizer": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "BehaviorPlanner$Lanelet2GlobalPlanner": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "BehaviorPlanner$ParkingPlanner": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "BehaviorPlanner$LanePlanner": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "BehaviorPlanner$Lanelet2MapLoader": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "BehaviorPlanner$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "EuclideanClusterDetector$RayGroundFilter": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "EuclideanClusterDetector$EuclideanClusterSettings": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "EuclideanClusterDetector$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "EuclideanClusterSettings$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "FrontLidarDriver$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "IntersectionOutput$EuclideanIntersection": { + "coreId": 1, + "unescapedStepName": "", + "factoryType": 1 + }, + "IntersectionOutput$parameter_events": { + "coreId": 1, + "unescapedStepName": "", + "factoryType": 1 + }, + "LanePlanner$Lanelet2MapLoader": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "LanePlanner$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2GlobalPlanner$Visualizer": { + "coreId": 0, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2GlobalPlanner$NDTLocalizer": { + "coreId": 0, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2GlobalPlanner$parameter_events": { + "coreId": 0, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2Map$parameter_events": { + "coreId": 1, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2MapLoader$Lanelet2Map": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2MapLoader$Lanelet2GlobalPlanner": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2MapLoader$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "MPCController$BehaviorPlanner": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "MPCController$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "NDTLocalizer$VoxelGridDownsampler": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "NDTLocalizer$PointCloudMapLoader": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "NDTLocalizer$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "ObjectCollisionEstimator$EuclideanClusterDetector": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "ObjectCollisionEstimator$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "ParkingPlanner$Lanelet2MapLoader": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "ParkingPlanner$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointCloudFusion$PointsTransformerFront": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointCloudFusion$PointsTransformerRear": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointCloudFusion$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointCloudMap$parameter_events": { + "coreId": 0, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointCloudMapLoader$PointCloudMap": { + "coreId": 1, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointCloudMapLoader$parameter_events": { + "coreId": 1, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointsTransformerFront$FrontLidarDriver": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointsTransformerFront$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointsTransformerRear$RearLidarDriver": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointsTransformerRear$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "RayGroundFilter$PointCloudFusion": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "RayGroundFilter$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "RearLidarDriver$parameter_events": { + "coreId": 0, + "unescapedStepName": "", + "factoryType": 1 + }, + "VehicleDBWSystem$VehicleInterface": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "VehicleDBWSystem$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "VehicleInterface$MPCController": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "VehicleInterface$BehaviorPlanner": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "VehicleInterface$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "Visualizer$parameter_events": { + "coreId": 0, + "unescapedStepName": "", + "factoryType": 1 + }, + "VoxelGridDownsampler$PointCloudFusion": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "VoxelGridDownsampler$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + } + }, + "parallised_layers": [] +} \ No newline at end of file diff --git a/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp b/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp index 787f1899..2daad682 100644 --- a/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp +++ b/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp @@ -13,7 +13,6 @@ // limitations under the License. #include "rclcpp/rclcpp.hpp" -#include #include "reference_system/system/type/rclcpp_system.hpp" #include "autoware_reference_system/autoware_system_builder.hpp" @@ -21,6 +20,7 @@ #include "autoware_reference_system/system/timing/default.hpp" #include +#include "config.h" int main(int argc, char * argv[]) { @@ -33,52 +33,8 @@ int main(int argc, char * argv[]) auto nodes = create_autoware_nodes(); - kpsr::mem::MemEnv environment; - /* - environment.setPropertyString("container_name", "eventLoop_systemRef"); - environment.setPropertyString("admin_log_filename", ""); - environment.setPropertyString("stat_filename", "/home/ubuntu/development/ros2/ref_results/ros_ref.csv"); - environment.setPropertyString("streaming_conf_file", "/home/ubuntu/development/ros2/ref_results/outputPolicy.json"); - environment.setPropertyString("log_filename", "/home/ubuntu/development/ros2/ref_results/ros_ref.log"); - - environment.setPropertyInt("log_level", 2); - environment.setPropertyInt("pool_size", 100); - environment.setPropertyInt("number_of_cores", 3); - environment.setPropertyInt("critical_thread_pool_size", 16); - environment.setPropertyInt("non_critical_thread_pool_size", 1); - environment.setPropertyInt("number_of_parallel_threads", 0); - environment.setPropertyInt("stat_log_interval_ms", 1000); - environment.setPropertyInt("admin_log_interval", 1000); - - environment.setPropertyBool("to_std_out", true); - environment.setPropertyBool("log_to_file", true); - environment.setPropertyBool("admin_log_to_file", false); - environment.setPropertyBool("stat_socket_container_enable", false); - environment.setPropertyBool("stat_file_container_enable", true); - environment.setPropertyBool("use_default_streaming_factory", true); - environment.setPropertyBool("test_dnn", false); - environment.setPropertyBool("export_streaming_configuration", true); - */ - environment.setPropertyString("log_filename", ""); - environment.setPropertyInt("log_level", 6); - environment.setPropertyInt("pool_size", 1); - environment.setPropertyInt("number_of_cores", 4);//1,2,3,4 - environment.setPropertyInt("number_of_trypost", 0); - environment.setPropertyInt("critical_thread_pool_size", 32); - environment.setPropertyInt("non_critical_thread_pool_size", 32); - environment.setPropertyInt("number_of_parallel_threads", 0); - - // - environment.setPropertyInt("stat_log_interval_ms", 1000); - environment.setPropertyBool("stat_file_container_enable", false); - environment.setPropertyString("stat_filename", "/home/ubuntu/development/klepsydra/reference_system/stats/benchmarks_internal_sub.csv"); - // - environment.setPropertyString("streaming_conf_file", "/home/ubuntu/development/klepsydra/reference_system/policy.json"); - environment.setPropertyBool("use_default_streaming_factory", false); - environment.setPropertyBool("test_dnn", false); - environment.setPropertyBool("export_streaming_configuration", false); - - rclcpp::Executor::SharedPtr executor = kpsr::ros2::StreamingExecutorFactory::createExecutor(&environment); + const std::string jsonFileName = std::string(CONF_DATA) + std::string("/streaming_conf.json"); + rclcpp::Executor::SharedPtr executor = kpsr::ros2::StreamingExecutorFactory::createExecutor(jsonFileName); for (auto & node : nodes) { executor->add_node(node); From 14220d487fcd8859ff85cd609d3ad737aaab553a Mon Sep 17 00:00:00 2001 From: Guillermo Sarabia Date: Tue, 23 May 2023 13:58:03 +0200 Subject: [PATCH 07/11] Add dockerfile and requirements. --- Dockerfile | 104 +++++++++++++++++++++++++++++++++++++++++++++++ requirements.txt | 4 ++ 2 files changed, 108 insertions(+) create mode 100644 Dockerfile create mode 100644 requirements.txt diff --git a/Dockerfile b/Dockerfile new file mode 100644 index 00000000..07e341f9 --- /dev/null +++ b/Dockerfile @@ -0,0 +1,104 @@ +# syntax=docker/dockerfile:1.4 +# Build with +# TODO: Not use root! +# Add cache for apt update.xº +ARG image_base=337955887028.dkr.ecr.eu-central-1.amazonaws.com/amd64:galactic-1.4.4 + +ARG registry=registry.klepsydra.io/repository +ARG board=amd64 +ARG osrelease=focal + +FROM $image_base as system_dep +ENV BUILD_MODE=Release + +USER root + +# Install kpe dependencies. VPN required. +# COPY public.gpg.key /tmp/public.gpg.key + +RUN <> /etc/apt/sources.list.d/klepsydra.list +# apt-key add /tmp/public.gpg.key +# rm /tmp/public.gpg.key +# apt update + +pip3 config set global.extra-index-url https://registry.klepsydra.io/repository/kpe-pypi/simple +pip3 install kpsr-codegen +EOF + +RUN mkdir -p -m 0700 ~/.ssh && ssh-keyscan github.com >> ~/.ssh/known_hosts + +FROM system_dep as kpe-core +ENV KPE_CORE_TAG=v7.11.0 +RUN --mount=type=ssh git clone --branch ${KPE_CORE_TAG} --recurse-submodules git@github.com:klepsydra-technologies/kpe-core + +RUN --mount=type=cache,target=/home/kpsruser/.ccache < Date: Wed, 31 May 2023 10:44:51 +0200 Subject: [PATCH 08/11] Update dockerfile --- Dockerfile | 13 ++++++++++++- .../src/ros2/data/streaming_conf.json.in | 6 +++--- 2 files changed, 15 insertions(+), 4 deletions(-) diff --git a/Dockerfile b/Dockerfile index 07e341f9..2711c2c0 100644 --- a/Dockerfile +++ b/Dockerfile @@ -2,7 +2,7 @@ # Build with # TODO: Not use root! # Add cache for apt update.xº -ARG image_base=337955887028.dkr.ecr.eu-central-1.amazonaws.com/amd64:galactic-1.4.4 +ARG image_base=registry.klepsydra.io/amd64/galactic:20.04.0 ARG registry=registry.klepsydra.io/repository ARG board=amd64 @@ -99,6 +99,17 @@ cd /home/kpsruser/colcon_reference-system/ colcon build --cmake-args -DCMAKE_PREFIX_PATH="/home/kpsruser/kpe-ros2-core-install/install" -DCMAKE_BUILD_TYPE=${BUILD_MODE} -DRUN_BENCHMARK=ON EOF +# ToDO: This is not ideal. # Necessary. ENV LD_LIBRARY_PATH=/home/kpsruser/kpe-ros2-core-install/install/kpsr_ros2_executor/lib:/usr/local/lib:/home/kpsruser/colcon_reference-system/install/reference_interfaces/lib:/opt/ros/galactic/lib/x86_64-linux-gnu:/opt/ros/galactic/lib +ENV PYTHONPATH=/opt/ros/galactic/lib/python3.8/site-packages:/home/kpsruser/colcon_reference-system/install/reference_system/lib/python3.8/site-packages/ +# Modify entrypoint +RUN sed -i '/^exec */i source /home/kpsruser/colcon_reference-system/install/setup.sh --' /opt/ros_entrypoint.sh + +# Install dependencies. +RUN pip3 install pandas==2.0.1 bokeh==2.4.1 psrecord==1.2 numpy==1.24.3 + +RUN chmod +x /home/kpsruser/reference-system/autoware_reference_system/scripts/benchmark.py +WORKDIR /home/kpsruser/reference-system/ +CMD autoware_reference_system/scripts/benchmark.py 30 autoware_default_custom \ No newline at end of file diff --git a/autoware_reference_system/src/ros2/data/streaming_conf.json.in b/autoware_reference_system/src/ros2/data/streaming_conf.json.in index 44562a5e..7d573c82 100644 --- a/autoware_reference_system/src/ros2/data/streaming_conf.json.in +++ b/autoware_reference_system/src/ros2/data/streaming_conf.json.in @@ -16,9 +16,9 @@ "pool_size": 1, "stat_admin_port": 9595, "stat_system_port": 9696, - "log_level": 0, - "number_of_event_loops": 4, - "number_of_cores": 4, + "log_level": 6, + "number_of_event_loops": 8, + "number_of_cores": 8, "critical_thread_pool_size": 32, "non_critical_thread_pool_size": 32, "number_of_parallel_threads": 1 From 484421dd3e017d9f139a7bee3f94d5b8d32888ad Mon Sep 17 00:00:00 2001 From: mruedac Date: Thu, 1 Jun 2023 18:25:33 +0200 Subject: [PATCH 09/11] Add version to Dockerfile. Create dockerfile for humble --- Dockerfile | 3 +- DockerfileHumble | 211 +++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 213 insertions(+), 1 deletion(-) create mode 100644 DockerfileHumble diff --git a/Dockerfile b/Dockerfile index 2711c2c0..ec299414 100644 --- a/Dockerfile +++ b/Dockerfile @@ -70,7 +70,8 @@ EOF # Install colcon, rosdep and dependencies FROM kpe-streaming as kpe-ros2-core -RUN --mount=type=ssh git clone --recurse-submodules git@github.com:klepsydra-technologies/kpe-ros2-core.git +ENV KPE_ROS2_CORE_VER=v1.0.0 +RUN --mount=type=ssh git clone --branch ${KPE_ROS2_CORE_VER} --recurse-submodules git@github.com:klepsydra-technologies/kpe-ros2-core.git ENV SSL_CERT_FILE=/etc/ssl/certs/ca-certificates.crt RUN --mount=type=cache,target=/home/kpsruser/.ccache <> /etc/sudoers + +ENV BUILD_MODE=Release + +ARG OPENSSLVERSION="OpenSSL_1_1_1i" +RUN git clone https://github.com/openssl/openssl.git && \ + cd openssl && git checkout ${OPENSSLVERSION} && \ + ./config -fPIC shared && \ + make -j$(nproc) && \ + make install && \ + cd ../ && rm -rf openssl + +ARG YAMLCPPVERSION="yaml-cpp-0.7.0" +RUN git clone https://github.com/jbeder/yaml-cpp && \ + cd yaml-cpp && git checkout ${YAMLCPPVERSION} && \ + mkdir build && \ + cd build && \ + cmake -DCMAKE_POSITION_INDEPENDENT_CODE=ON -DYAML_CPP_BUILD_TESTS=Off ../ && \ + make -j$(nproc) && \ + make install && \ + cd ../../ && rm -rf yaml-cpp + +ARG ZMQVERSION="v4.3.4" +RUN git clone https://github.com/zeromq/libzmq.git && \ + cd libzmq && \ + git checkout ${ZMQVERSION} && \ + mkdir build && \ + cd build && \ + cmake ../ && \ + make -j$(nproc) && \ + make install && \ + cd ../../ && rm -rf libzmq + +ARG ZMQCPPVERSION="v4.8.0" +RUN git clone https://github.com/zeromq/cppzmq.git && \ + cd cppzmq && \ + git checkout ${ZMQCPPVERSION} && \ + mkdir build && cd build && \ + cmake ../ && \ + make -j$(nproc) && \ + make install && \ + cd ../../ && rm -rf cppzmq + +ARG BENCHMARKVERSION="3b3de69400164013199ea448f051d94d7fc7d81f" +RUN git clone https://github.com/google/benchmark.git && \ + cd benchmark && \ + git checkout ${BENCHMARKVERSION} && \ + mkdir build && cd build && \ + cmake -DBENCHMARK_DOWNLOAD_DEPENDENCIES=on -DCMAKE_BUILD_TYPE=Release ../ && \ + make -j$(nproc) && \ + make install && \ + cd ../../ && \ + rm -rf benchmark + +RUN apt-get -y update && apt-get -y install libtool + +ARG PROTOBUFVERSION="v3.19.0" +RUN git clone https://github.com/protocolbuffers/protobuf.git && \ + cd protobuf && \ + git checkout ${PROTOBUFVERSION} && \ + git submodule update --init --recursive && \ + ./autogen.sh && ./configure && \ + make -j$(nproc) && \ + sudo make install && ldconfig && \ + cd ../../ && \ + rm -rf protobuf + +ARG EIGENVERSION="3.4.0" +RUN git clone https://gitlab.com/libeigen/eigen.git && \ + cd eigen && \ + git checkout ${EIGENVERSION} && \ + mkdir build && cd build && \ + cmake -DCMAKE_BUILD_TYPE=Release ../ && \ + make -j$(nproc) && \ + sudo make install && \ + cd ../../ && \ + rm -rf eigen + +ARG OPENCVVERSION="3.4.17" +RUN git clone https://github.com/opencv/opencv.git && \ + cd opencv && \ + git checkout ${OPENCVVERSION} && \ + mkdir build && cd build && \ + cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_PERF_TESTS=OFF -DBUILD_TESTS=OFF -DINSTALL_TESTS=OFF -DINSTALL_PYTHON_EXAMPLES=OFF -DINSTALL_C_EXAMPLES=OFF -DBUILD_opencv_apps=OFF ../ && \ + make -j$(nproc) && \ + sudo make install && \ + cd ../../ && \ + rm -rf opencv + + +USER root +WORKDIR /home/kpsruser +RUN <> /etc/apt/sources.list.d/klepsydra.list +# apt-key add /tmp/public.gpg.key +# rm /tmp/public.gpg.key +# apt update +apt-get -y install python3-pip +pip config set global.extra-index-url https://registry.klepsydra.io/repository/kpe-pypi/simple +pip install kpsr-codegen +EOF + +RUN mkdir -p -m 0700 ~/.ssh && ssh-keyscan github.com >> ~/.ssh/known_hosts + +FROM system_dep as kpe-core + + + +ENV KPE_CORE_TAG=v8.0.0 +RUN --mount=type=ssh git clone --branch ${KPE_CORE_TAG} --recurse-submodules git@github.com:klepsydra-technologies/kpe-core +RUN --mount=type=cache,target=/home/kpsruser/.ccache <> /home/kpsruser/.bashrc && + echo 'source /home/kpsruser/colcon_reference-system/install/setup.sh' >> /home/kpsruser/.bashrc && + echo 'source /home/kpsruser/kpe-ros2-core-install/install/setup.sh' >> /home/kpsruser/.bashrc From bb19647f854ae448e2ad67f5de04e780460ae370 Mon Sep 17 00:00:00 2001 From: mruedac Date: Wed, 21 Jun 2023 18:56:32 +0200 Subject: [PATCH 10/11] Fixes for using genetic_algo script --- Dockerfile | 2 +- DockerfileHumble | 2 +- .../src/ros2/data/streaming_policy_ref.json | 289 ++++++++++++++++++ genetic_algo/genetic_algorithm.py | 17 +- 4 files changed, 301 insertions(+), 9 deletions(-) create mode 100644 autoware_reference_system/src/ros2/data/streaming_policy_ref.json diff --git a/Dockerfile b/Dockerfile index ec299414..f50f978d 100644 --- a/Dockerfile +++ b/Dockerfile @@ -109,7 +109,7 @@ ENV PYTHONPATH=/opt/ros/galactic/lib/python3.8/site-packages:/home/kpsruser/colc RUN sed -i '/^exec */i source /home/kpsruser/colcon_reference-system/install/setup.sh --' /opt/ros_entrypoint.sh # Install dependencies. -RUN pip3 install pandas==2.0.1 bokeh==2.4.1 psrecord==1.2 numpy==1.24.3 +RUN pip3 install pandas==2.0.1 bokeh==2.4.1 psrecord==1.2 numpy==1.23.5 pygad==2.18.1 RUN chmod +x /home/kpsruser/reference-system/autoware_reference_system/scripts/benchmark.py WORKDIR /home/kpsruser/reference-system/ diff --git a/DockerfileHumble b/DockerfileHumble index dd179590..aafe175c 100644 --- a/DockerfileHumble +++ b/DockerfileHumble @@ -196,7 +196,7 @@ colcon build --cmake-args -DCMAKE_PREFIX_PATH="/home/kpsruser/kpe-ros2-core-inst EOF RUN apt-get -y install ros-humble-rmw-cyclonedds-cpp -RUN pip install pandas==2.0.1 bokeh==2.4.1 psrecord==1.2 numpy==1.24.3 +RUN pip install pandas==2.0.1 bokeh==2.4.1 psrecord==1.2 numpy==1.23.5 RUN chmod +x /home/kpsruser/reference-system/autoware_reference_system/scripts/benchmark.py # Necessary. ENV LD_LIBRARY_PATH=/home/kpsruser/kpe-ros2-core-install/install/kpsr_ros2_executor/lib:/usr/local/lib:/home/kpsruser/colcon_reference-system/install/reference_interfaces/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib diff --git a/autoware_reference_system/src/ros2/data/streaming_policy_ref.json b/autoware_reference_system/src/ros2/data/streaming_policy_ref.json new file mode 100644 index 00000000..ced1eaef --- /dev/null +++ b/autoware_reference_system/src/ros2/data/streaming_policy_ref.json @@ -0,0 +1,289 @@ +{ + "pool_size": 1, + "number_of_cores": 4, + "number_of_event_loops": 4, + "number_of_parallel_threads": 1, + "non_critical_thread_pool_size": 32, + "event_loop_core_map": { + "0": [ + 0 + ], + "1": [ + 1 + ], + "2": [ + 2 + ], + "3": [ + 3 + ] + }, + "layer_event_loop_map": { + "BehaviorPlanner$ObjectCollisionEstimator": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "BehaviorPlanner$NDTLocalizer": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "BehaviorPlanner$Lanelet2GlobalPlanner": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "BehaviorPlanner$ParkingPlanner": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "BehaviorPlanner$LanePlanner": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "BehaviorPlanner$Lanelet2MapLoader": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "BehaviorPlanner$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "EuclideanClusterDetector$RayGroundFilter": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "EuclideanClusterDetector$EuclideanClusterSettings": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "EuclideanClusterDetector$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "EuclideanClusterSettings$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "FrontLidarDriver$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "IntersectionOutput$EuclideanIntersection": { + "coreId": 1, + "unescapedStepName": "", + "factoryType": 1 + }, + "IntersectionOutput$parameter_events": { + "coreId": 1, + "unescapedStepName": "", + "factoryType": 1 + }, + "LanePlanner$Lanelet2MapLoader": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "LanePlanner$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2GlobalPlanner$Visualizer": { + "coreId": 0, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2GlobalPlanner$NDTLocalizer": { + "coreId": 0, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2GlobalPlanner$parameter_events": { + "coreId": 0, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2Map$parameter_events": { + "coreId": 1, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2MapLoader$Lanelet2Map": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2MapLoader$Lanelet2GlobalPlanner": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "Lanelet2MapLoader$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "MPCController$BehaviorPlanner": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "MPCController$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "NDTLocalizer$VoxelGridDownsampler": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "NDTLocalizer$PointCloudMapLoader": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "NDTLocalizer$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "ObjectCollisionEstimator$EuclideanClusterDetector": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "ObjectCollisionEstimator$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "ParkingPlanner$Lanelet2MapLoader": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "ParkingPlanner$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointCloudFusion$PointsTransformerFront": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointCloudFusion$PointsTransformerRear": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointCloudFusion$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointCloudMap$parameter_events": { + "coreId": 0, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointCloudMapLoader$PointCloudMap": { + "coreId": 1, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointCloudMapLoader$parameter_events": { + "coreId": 1, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointsTransformerFront$FrontLidarDriver": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointsTransformerFront$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointsTransformerRear$RearLidarDriver": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "PointsTransformerRear$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "RayGroundFilter$PointCloudFusion": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "RayGroundFilter$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "RearLidarDriver$parameter_events": { + "coreId": 0, + "unescapedStepName": "", + "factoryType": 1 + }, + "VehicleDBWSystem$VehicleInterface": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "VehicleDBWSystem$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "VehicleInterface$MPCController": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "VehicleInterface$BehaviorPlanner": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "VehicleInterface$parameter_events": { + "coreId": 3, + "unescapedStepName": "", + "factoryType": 1 + }, + "Visualizer$parameter_events": { + "coreId": 0, + "unescapedStepName": "", + "factoryType": 1 + }, + "VoxelGridDownsampler$PointCloudFusion": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + }, + "VoxelGridDownsampler$parameter_events": { + "coreId": 2, + "unescapedStepName": "", + "factoryType": 1 + } + }, + "parallelised_layers": [] +} \ No newline at end of file diff --git a/genetic_algo/genetic_algorithm.py b/genetic_algo/genetic_algorithm.py index c4e0cb39..901fce23 100644 --- a/genetic_algo/genetic_algorithm.py +++ b/genetic_algo/genetic_algorithm.py @@ -8,8 +8,10 @@ from reference_system_py.benchmark import get_benchmark_directories_below, generate_trace from reference_system_py.std_latency import parseLogSummaryFromFiles -n_number_cruncher = 4096 -with open('policy_ref_def.json') as f: +n_number_cruncher = 4096 # from: +# /home/kpsruser/colcon_reference-system/src/reference-system/autoware_reference_system/include/autoware_reference_system/system/timing/default.hpp +with open('/home/kpsruser/colcon_reference-system/src/reference-system/autoware_reference_system/src/ros2/data/streaming_policy_ref.json') as f: + # policy_template = json.load(f) edges = [('FrontLidarDriver', 'PointsTransformerFront'), @@ -70,8 +72,8 @@ def fitness_func(solution, idx_sol): print(idx_sol) + print(solution) update_policy(solution) - latency_hot_path = calculate_latency_policy() return -latency_hot_path @@ -85,7 +87,7 @@ def update_policy(solution): if node in node_dicts: base_policy['layer_event_loop_map'][composite_node]['coreId'] = int(node_dicts[node]) # Execute. - with open('/home/ubuntu/development/klepsydra/reference_system/policy.json', 'w', encoding='utf-8') as f: + with open('/home/kpsruser/colcon_reference-system/src/reference-system/autoware_reference_system/src/ros2/data/streaming_policy.json', 'w', encoding='utf-8') as f: json.dump(base_policy, f, ensure_ascii=False, indent=4) @@ -121,7 +123,7 @@ def calculate_latency_policy(): num_genes = len(hot_path_nodes) + len(other_nodes) init_range_low = 0 -init_range_high = 3 +init_range_high = 4 # not included parent_selection_type = "sss" keep_parents = 1 @@ -153,8 +155,9 @@ def calculate_latency_policy(): solution, solution_fitness, solution_idx = ga_instance.best_solution() update_policy(solution) -src = '/home/ubuntu/development/klepsydra/reference_system/policy.json' -dst = f'/home/ubuntu/development/klepsydra/reference_system/policy_{n_number_cruncher}.json' +src = '/home/kpsruser/colcon_reference-system/src/reference-system/autoware_reference_system/src/ros2/data/streaming_policy.json' +dst = f'/home/kpsruser/colcon_reference-system/src/reference-system/autoware_reference_system/src/ros2/data/policy_{n_number_cruncher}.json' + shutil.copyfile(src, dst) From b712eac63e8f29c3696db186df1349d57c03e6b0 Mon Sep 17 00:00:00 2001 From: mruedac Date: Wed, 21 Jun 2023 19:10:10 +0200 Subject: [PATCH 11/11] Add humbleRPI image --- DockerfileHumble | 8 +- DockerfileHumbleRPI | 213 ++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 217 insertions(+), 4 deletions(-) create mode 100644 DockerfileHumbleRPI diff --git a/DockerfileHumble b/DockerfileHumble index aafe175c..1fb2d1f4 100644 --- a/DockerfileHumble +++ b/DockerfileHumble @@ -164,7 +164,7 @@ EOF # Install colcon, rosdep and dependencies FROM kpe-streaming as kpe-ros2-core -ENV KPE_ROS2_CORE_BRANCH=KPE-537-Fixing-dependencies-for-ros2-humble +ENV KPE_ROS2_CORE_BRANCH=humble RUN --mount=type=ssh git clone --branch ${KPE_ROS2_CORE_BRANCH} --recurse-submodules git@github.com:klepsydra-technologies/kpe-ros2-core.git ENV SSL_CERT_FILE=/etc/ssl/certs/ca-certificates.crt @@ -196,7 +196,7 @@ colcon build --cmake-args -DCMAKE_PREFIX_PATH="/home/kpsruser/kpe-ros2-core-inst EOF RUN apt-get -y install ros-humble-rmw-cyclonedds-cpp -RUN pip install pandas==2.0.1 bokeh==2.4.1 psrecord==1.2 numpy==1.23.5 +RUN pip install pandas==2.0.1 bokeh==2.4.1 psrecord==1.2 numpy==1.23.5 pygad==2.18.1 RUN chmod +x /home/kpsruser/reference-system/autoware_reference_system/scripts/benchmark.py # Necessary. ENV LD_LIBRARY_PATH=/home/kpsruser/kpe-ros2-core-install/install/kpsr_ros2_executor/lib:/usr/local/lib:/home/kpsruser/colcon_reference-system/install/reference_interfaces/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib @@ -206,6 +206,6 @@ RUN sed -i 's/parallised/parallelised/g' /home/kpsruser/colcon_reference-system/ USER kpsruser -RUN echo 'source /opt/ros/humble/setup.sh' >> /home/kpsruser/.bashrc && - echo 'source /home/kpsruser/colcon_reference-system/install/setup.sh' >> /home/kpsruser/.bashrc && +RUN echo 'source /opt/ros/humble/setup.sh' >> /home/kpsruser/.bashrc && \ + echo 'source /home/kpsruser/colcon_reference-system/install/setup.sh' >> /home/kpsruser/.bashrc && \ echo 'source /home/kpsruser/kpe-ros2-core-install/install/setup.sh' >> /home/kpsruser/.bashrc diff --git a/DockerfileHumbleRPI b/DockerfileHumbleRPI new file mode 100644 index 00000000..02ad7b2f --- /dev/null +++ b/DockerfileHumbleRPI @@ -0,0 +1,213 @@ +ARG image_base=arm64v8/ros:humble +ARG registry=registry.klepsydra.io/repository +ARG board=amd64 +ARG osrelease=jammy + +FROM $image_base as system_dep + +ENV TZ 'Europe/Madrid' +ENV LC_ALL en_US.UTF-8 +ENV LANG en_US.UTF-8 +ENV LANGUAGE en_US.UTF-8 +ENV DEBIAN_FRONTEND=noninteractive +RUN groupadd --gid 10000 kpsruser && \ + useradd --uid 10000 --gid kpsruser --shell /bin/bash --create-home kpsruser && \ + usermod -aG sudo kpsruser && \ + echo '%sudo ALL=(ALL) NOPASSWD:ALL' >> /etc/sudoers + +RUN apt update && apt-get -y install openssh-client +RUN mkdir -p -m 0700 ~/.ssh +RUN ssh-keyscan github.com >> ~/.ssh/known_hosts + +ENV BUILD_MODE=Release + +ARG OPENSSLVERSION="OpenSSL_1_1_1i" +RUN git clone https://github.com/openssl/openssl.git && \ + cd openssl && git checkout ${OPENSSLVERSION} && \ + ./config -fPIC shared && \ + make -j$(nproc) && \ + make install && \ + cd ../ && rm -rf openssl + + + +RUN apt-get -y install libtool + +ARG PROTOBUFVERSION="v3.19.0" +RUN git clone https://github.com/protocolbuffers/protobuf.git && \ + cd protobuf && \ + git checkout ${PROTOBUFVERSION} && \ + git submodule update --init --recursive && \ + ./autogen.sh && ./configure && \ + make -j$(nproc) && \ + sudo make install && ldconfig && \ + cd ../../ && \ + rm -rf protobuf + +ARG EIGENVERSION="3.4.0" +RUN git clone https://gitlab.com/libeigen/eigen.git && \ + cd eigen && \ + git checkout ${EIGENVERSION} && \ + mkdir build && cd build && \ + cmake -DCMAKE_BUILD_TYPE=Release ../ && \ + make -j$(nproc) && \ + sudo make install && \ + cd ../../ && \ + rm -rf eigen + +ARG OPENCVVERSION="3.4.17" +RUN git clone https://github.com/opencv/opencv.git && \ + cd opencv && \ + git checkout ${OPENCVVERSION} && \ + mkdir build && cd build && \ + cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_PERF_TESTS=OFF -DBUILD_TESTS=OFF -DINSTALL_TESTS=OFF -DINSTALL_PYTHON_EXAMPLES=OFF -DINSTALL_C_EXAMPLES=OFF -DBUILD_opencv_apps=OFF ../ && \ + make -j$(nproc) && \ + sudo make install && \ + cd ../../ && \ + rm -rf opencv + +ARG BENCHMARKVERSION="3b3de69400164013199ea448f051d94d7fc7d81f" +RUN git clone https://github.com/google/benchmark.git && \ + cd benchmark && \ + git checkout ${BENCHMARKVERSION} && \ + mkdir build && cd build && \ + cmake -DBENCHMARK_DOWNLOAD_DEPENDENCIES=on -DCMAKE_BUILD_TYPE=Release ../ && \ + make -j$(nproc) && \ + make install && \ + cd ../../ && \ + rm -rf benchmark + +ARG ZMQVERSION="v4.3.4" +RUN git clone https://github.com/zeromq/libzmq.git && \ + cd libzmq && \ + git checkout ${ZMQVERSION} && \ + mkdir build && \ + cd build && \ + cmake ../ && \ + make -j$(nproc) && \ + make install && \ + cd ../../ && rm -rf libzmq + +ARG ZMQCPPVERSION="v4.8.0" +RUN git clone https://github.com/zeromq/cppzmq.git && \ + cd cppzmq && \ + git checkout ${ZMQCPPVERSION} && \ + mkdir build && cd build && \ + cmake ../ && \ + make -j$(nproc) && \ + make install && \ + cd ../../ && rm -rf cppzmq +ARG YAMLCPPVERSION="yaml-cpp-0.7.0" +RUN git clone https://github.com/jbeder/yaml-cpp && \ + cd yaml-cpp && git checkout ${YAMLCPPVERSION} && \ + mkdir build && \ + cd build && \ + cmake -DCMAKE_POSITION_INDEPENDENT_CODE=ON -DYAML_CPP_BUILD_TESTS=Off ../ && \ + make -j$(nproc) && \ + make install && \ + cd ../../ && rm -rf yaml-cpp + +USER root +WORKDIR /home/kpsruser +RUN <> /etc/apt/sources.list.d/klepsydra.list +# apt-key add /tmp/public.gpg.key +# rm /tmp/public.gpg.key +# apt update +apt-get -y install python3-pip +pip config set global.extra-index-url https://registry.klepsydra.io/repository/kpe-pypi/simple +pip install kpsr-codegen +EOF + +RUN mkdir -p -m 0700 ~/.ssh && ssh-keyscan github.com >> ~/.ssh/known_hosts + +FROM system_dep as kpe-core + + + +ENV KPE_CORE_TAG=v8.0.0 +RUN --mount=type=ssh git clone --branch ${KPE_CORE_TAG} --recurse-submodules git@github.com:klepsydra-technologies/kpe-core +RUN --mount=type=cache,target=/home/kpsruser/.ccache <> /home/kpsruser/.bashrc && + echo 'source /home/kpsruser/colcon_reference-system/install/setup.sh' >> /home/kpsruser/.bashrc && + echo 'source /home/kpsruser/kpe-ros2-core-install/install/setup.sh' >> /home/kpsruser/.bashrc