|
| 1 | +// Copyright 2021 Robert Bosch GmbH |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include <memory> |
| 16 | +#include <string> |
| 17 | +#include <vector> |
| 18 | +#include <unordered_set> |
| 19 | +#include <unordered_map> |
| 20 | +#include <set> |
| 21 | +#include <optional> |
| 22 | + |
| 23 | +#include "rclcpp/rclcpp.hpp" |
| 24 | +#include "rcpputils/thread.hpp" |
| 25 | +#include "rcl/context.h" |
| 26 | +#include "rcutils/thread_attr.h" |
| 27 | + |
| 28 | +#include "reference_system/system/type/rclcpp_system.hpp" |
| 29 | + |
| 30 | +#include "autoware_reference_system/autoware_system_builder.hpp" |
| 31 | +#include "autoware_reference_system/system/timing/benchmark.hpp" |
| 32 | +#include "autoware_reference_system/system/timing/default.hpp" |
| 33 | +#include "autoware_reference_system/priorities.hpp" |
| 34 | + |
| 35 | +#ifdef USE_USER_IMPLEMENTED_ATTR_FIND_ROUTINE |
| 36 | +std::optional<rcpputils::ThreadAttribute> find_thread_attr(const std::string & name) |
| 37 | +{ |
| 38 | + rcl_context_t const * ctx = rclcpp::contexts::get_global_default_context()->get_rcl_context().get(); |
| 39 | + rcutils_thread_attrs_t * rcl_attrs = rcl_context_get_thread_attrs(ctx); |
| 40 | + |
| 41 | + if (!rcl_attrs) { |
| 42 | + return std::nullopt; |
| 43 | + } |
| 44 | + |
| 45 | + for (std::size_t i = 0; i < rcl_attrs->num_attributes; ++i) { |
| 46 | + if (name == rcl_attrs->attributes[i].name) { |
| 47 | + rcutils_thread_attr_t const & rcl_attr = rcl_attrs->attributes[i]; |
| 48 | + rcpputils::ThreadAttribute attr(rcl_attr); |
| 49 | + return {attr}; |
| 50 | + } |
| 51 | + } |
| 52 | + |
| 53 | + return std::nullopt; |
| 54 | +} |
| 55 | +#endif // USE_USER_IMPLEMENTED_ATTR_FIND_ROUTINE |
| 56 | + |
| 57 | +int main(int argc, char ** argv) |
| 58 | +{ |
| 59 | + rclcpp::init(argc, argv); |
| 60 | + |
| 61 | + using TimeConfig = nodes::timing::Default; |
| 62 | + // uncomment for benchmarking |
| 63 | + // using TimeConfig = nodes::timing::BenchmarkCPUUsage; |
| 64 | + // set_benchmark_mode(true); |
| 65 | + |
| 66 | + auto nodes_vec = create_autoware_nodes<RclcppSystem, TimeConfig>(); |
| 67 | + using NodeMap = std::unordered_map<std::string, |
| 68 | + std::shared_ptr<RclcppSystem::NodeBaseType>>; |
| 69 | + |
| 70 | + NodeMap nodes; |
| 71 | + for (const auto & node : nodes_vec) { |
| 72 | + nodes.emplace(node->get_name(), node); |
| 73 | + std::cout << node->get_name() << "\n"; |
| 74 | + } |
| 75 | + |
| 76 | + |
| 77 | +#ifdef USE_USER_IMPLEMENTED_ATTR_FIND_ROUTINE |
| 78 | + auto logger = rclcpp::get_logger("autoware_default_prioritized"); |
| 79 | + auto hotpath_attr = find_thread_attr("RCLCPP_EXECUTOR_HOTPATH"); |
| 80 | + if (!hotpath_attr) { |
| 81 | + RCLCPP_ERROR(logger, "not found thread attribute \"RCLCPP_EXECUTOR_HOTPATH\""); |
| 82 | + return 1; |
| 83 | + } |
| 84 | + auto planner_attr= find_thread_attr("RCLCPP_EXECUTOR_PLANNER"); |
| 85 | + if (!planner_attr) { |
| 86 | + RCLCPP_ERROR(logger, "not found thread attribute \"RCLCPP_EXECUTOR_PLANNER\""); |
| 87 | + return 1; |
| 88 | + } |
| 89 | + |
| 90 | + rclcpp::executors::SingleThreadedExecutor front_exe(rclcpp::ExecutorOptions(), *hotpath_attr); |
| 91 | + rclcpp::executors::SingleThreadedExecutor rear_exe(rclcpp::ExecutorOptions(), *hotpath_attr); |
| 92 | + rclcpp::executors::SingleThreadedExecutor fusion_exe(rclcpp::ExecutorOptions(), *hotpath_attr); |
| 93 | + rclcpp::executors::SingleThreadedExecutor planner_exe(rclcpp::ExecutorOptions(), *planner_attr); |
| 94 | +#else // USE_USER_IMPLEMENTED_ATTR_FIND_ROUTINE |
| 95 | + auto front_exe_options = rclcpp::ExecutorOptions(); |
| 96 | + auto rear_exe_options = rclcpp::ExecutorOptions(); |
| 97 | + auto fusion_exe_options = rclcpp::ExecutorOptions(); |
| 98 | + auto planner_exe_options = rclcpp::ExecutorOptions(); |
| 99 | + front_exe_options.name = "RCLCPP_EXECUTOR_HOTPATH"; |
| 100 | + rear_exe_options.name = "RCLCPP_EXECUTOR_HOTPATH"; |
| 101 | + fusion_exe_options.name = "RCLCPP_EXECUTOR_HOTPATH"; |
| 102 | + planner_exe_options.name = "RCLCPP_EXECUTOR_PLANNER"; |
| 103 | + |
| 104 | + rclcpp::executors::SingleThreadedExecutor front_exe(front_exe_options); |
| 105 | + rclcpp::executors::SingleThreadedExecutor rear_exe(rear_exe_options); |
| 106 | + rclcpp::executors::SingleThreadedExecutor fusion_exe(fusion_exe_options); |
| 107 | + rclcpp::executors::SingleThreadedExecutor planner_exe(planner_exe_options); |
| 108 | +#endif // USE_USER_IMPLEMENTED_ATTR_FIND_ROUTINE |
| 109 | + rclcpp::executors::SingleThreadedExecutor other_exe; |
| 110 | + |
| 111 | + std::set<std::string> front_nodes = {"FrontLidarDriver", "PointsTransformerFront"}; |
| 112 | + std::set<std::string> rear_nodes = {"RearLidarDriver", "PointsTransformerRear"}; |
| 113 | + std::set<std::string> fusion_nodes = {"PointCloudFusion", |
| 114 | + "RayGroundFilter", |
| 115 | + "EuclideanClusterDetector", |
| 116 | + "ObjectCollisionEstimator"}; |
| 117 | + std::set<std::string> planner_nodes = {"BehaviorPlanner"}; |
| 118 | + std::set<std::string> other_nodes = {"PointCloudMap", |
| 119 | + "Visualizer", |
| 120 | + "Lanelet2Map", |
| 121 | + "EuclideanClusterSettings", |
| 122 | + "PointCloudMapLoader", |
| 123 | + "MPCController", |
| 124 | + "VehicleInterface", |
| 125 | + "VehicleDBWSystem", |
| 126 | + "NDTLocalizer", |
| 127 | + "Lanelet2GlobalPlanner", |
| 128 | + "Lanelet2MapLoader", |
| 129 | + "ParkingPlanner", |
| 130 | + "LanePlanner", |
| 131 | + "IntersectionOutput", |
| 132 | + "VoxelGridDownsampler"}; |
| 133 | + |
| 134 | + for (const auto & node : front_nodes) { |
| 135 | + front_exe.add_node(nodes.at(node)); |
| 136 | + } |
| 137 | + for (const auto & node : rear_nodes) { |
| 138 | + rear_exe.add_node(nodes.at(node)); |
| 139 | + } |
| 140 | + for (const auto & node : fusion_nodes) { |
| 141 | + std::cout << node << "\n"; |
| 142 | + fusion_exe.add_node(nodes.at(node)); |
| 143 | + } |
| 144 | + for (const auto & node : planner_nodes) { |
| 145 | + planner_exe.add_node(nodes.at(node)); |
| 146 | + } |
| 147 | + for (const auto & node : other_nodes) { |
| 148 | + other_exe.add_node(nodes.at(node)); |
| 149 | + } |
| 150 | + |
| 151 | + rcpputils::Thread front_thread {[&]() { |
| 152 | + front_exe.spin(); |
| 153 | + }}; |
| 154 | + rcpputils::Thread rear_thread {[&]() { |
| 155 | + rear_exe.spin(); |
| 156 | + }}; |
| 157 | + rcpputils::Thread fusion_thread {[&]() { |
| 158 | + fusion_exe.spin(); |
| 159 | + }}; |
| 160 | + rcpputils::Thread planner_thread {[&]() { |
| 161 | + planner_exe.spin(); |
| 162 | + }}; |
| 163 | + rcpputils::Thread other_thread {[&]() { |
| 164 | + other_exe.spin(); |
| 165 | + }}; |
| 166 | + |
| 167 | + front_thread.join(); |
| 168 | + rear_thread.join(); |
| 169 | + fusion_thread.join(); |
| 170 | + planner_thread.join(); |
| 171 | + |
| 172 | + rclcpp::shutdown(); |
| 173 | +} |
0 commit comments