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/Dockerfile b/Dockerfile new file mode 100644 index 00000000..f50f978d --- /dev/null +++ b/Dockerfile @@ -0,0 +1,116 @@ +# syntax=docker/dockerfile:1.4 +# Build with +# TODO: Not use root! +# Add cache for apt update.xº +ARG image_base=registry.klepsydra.io/amd64/galactic:20.04.0 + +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 <> /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 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 diff --git a/autoware_reference_system/CMakeLists.txt b/autoware_reference_system/CMakeLists.txt index af6dae6a..ceb6e1a7 100644 --- a/autoware_reference_system/CMakeLists.txt +++ b/autoware_reference_system/CMakeLists.txt @@ -20,6 +20,11 @@ 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(KlepsydraStreaming REQUIRED) + find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() @@ -58,9 +63,23 @@ if(${FRAMEWORK} STREQUAL ros) endif() # Add new executors to test here -#add_benchmark_executable(autoware_default_custom -# src/ros2/executor/autoware_default_custom.cpp -#) +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}) find_package(ament_lint_auto REQUIRED) @@ -75,9 +94,13 @@ if(${BUILD_TESTING}) endif() if(${RUN_BENCHMARK}) - # Test all executables by default. - # Modify this variable to test only a subset of executables - set(TEST_TARGETS ${BENCHMARK_EXECUTABLES}) + # Add executables here to test + set(TEST_TARGETS + autoware_default_singlethreaded + autoware_default_staticsinglethreaded + autoware_default_multithreaded + #autoware_default_custom + ) # Add more run times here (time to run traces for) set(RUN_TIMES diff --git a/autoware_reference_system/package.xml b/autoware_reference_system/package.xml index 83cd8a13..2cb48452 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/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..7d573c82 --- /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": 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 + } +} \ 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/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/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..2daad682 --- /dev/null +++ b/autoware_reference_system/src/ros2/executor/autoware_default_klepsydrasinglethreaded.cpp @@ -0,0 +1,48 @@ +// 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/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 "config.h" + +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(); + + 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); + } + executor->spin(); + + nodes.clear(); + rclcpp::shutdown(); + + return 0; +} diff --git a/genetic_algo/genetic_algorithm.py b/genetic_algo/genetic_algorithm.py new file mode 100644 index 00000000..901fce23 --- /dev/null +++ b/genetic_algo/genetic_algorithm.py @@ -0,0 +1,164 @@ +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 # 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'), +('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) + print(solution) + 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/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) + + +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 = 4 # not included + +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/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) + + +print(solution_fitness) \ No newline at end of file diff --git a/genetic_algo/requirements.txt b/genetic_algo/requirements.txt new file mode 100644 index 00000000..0f3c1669 --- /dev/null +++ b/genetic_algo/requirements.txt @@ -0,0 +1,3 @@ +bokeh==2.4.1 +psrecord==1.2 +pygad diff --git a/reference_system/include/reference_system/nodes/rclcpp/command.hpp b/reference_system/include/reference_system/nodes/rclcpp/command.hpp index 1b8b7fe6..b9a10905 100644 --- a/reference_system/include/reference_system/nodes/rclcpp/command.hpp +++ b/reference_system/include/reference_system/nodes/rclcpp/command.hpp @@ -43,7 +43,9 @@ class Command : public rclcpp::Node { uint32_t missed_samples = get_missed_samples_and_update_seq_nr(input_message, sequence_number_); + uint64_t timestamp = now_as_int(); 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 8b17a53d..d21f5397 100644 --- a/reference_system/include/reference_system/nodes/rclcpp/cyclic.hpp +++ b/reference_system/include/reference_system/nodes/rclcpp/cyclic.hpp @@ -88,6 +88,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 ee6e8008..91a05452 100644 --- a/reference_system/include/reference_system/nodes/rclcpp/fusion.hpp +++ b/reference_system/include/reference_system/nodes/rclcpp/fusion.hpp @@ -82,6 +82,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 ddf3380f..2806a066 100644 --- a/reference_system/include/reference_system/nodes/rclcpp/intersection.hpp +++ b/reference_system/include/reference_system/nodes/rclcpp/intersection.hpp @@ -88,6 +88,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 d7c7b6e4..6553e687 100644 --- a/reference_system/include/reference_system/nodes/rclcpp/sensor.hpp +++ b/reference_system/include/reference_system/nodes/rclcpp/sensor.hpp @@ -51,6 +51,7 @@ class Sensor : public rclcpp::Node 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 5758f61e..6c8e7c72 100644 --- a/reference_system/include/reference_system/nodes/rclcpp/transform.hpp +++ b/reference_system/include/reference_system/nodes/rclcpp/transform.hpp @@ -61,6 +61,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: diff --git a/requirements.txt b/requirements.txt index be29a158..6279ea00 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,2 +1,4 @@ bokeh==2.4.1 psrecord==1.2 +pygad +numpy==1.24.3 \ No newline at end of file