just always clear cmake cache + print selected build settings
This commit is contained in:
parent
8cd5b03b03
commit
3f73f85c66
4 changed files with 15 additions and 2 deletions
|
@ -37,11 +37,14 @@ TRACE_NAME="${SCHEDULER_TYPE}_${THREADING_TYPE}_${FUSION_TYPE}_${TRACE_LENGTH}"
|
||||||
|
|
||||||
cd "$LOCAL_PROJECT_DIR"
|
cd "$LOCAL_PROJECT_DIR"
|
||||||
|
|
||||||
colcon build --packages-select full_topology --cmake-args "${CMAKE_ARGS[@]}"
|
echo colcon build --packages-select full_topology --cmake-clean-cache --cmake-clean-first --cmake-args "${CMAKE_ARGS[@]}"
|
||||||
|
colcon build --packages-select full_topology --cmake-clean-cache --cmake-clean-first --cmake-args "${CMAKE_ARGS[@]}"
|
||||||
|
|
||||||
source install/setup.bash
|
source install/setup.bash
|
||||||
|
|
||||||
TRACE_ID=$(taskset -c 2,3 ros2 launch full_topology trace_full_topology.launch.py "length:=${TRACE_LENGTH}" | \
|
OUTPUT=$(taskset -c 2,3 ros2 launch full_topology trace_full_topology.launch.py "length:=${TRACE_LENGTH}")
|
||||||
|
#echo ${OUTPUT}
|
||||||
|
TRACE_ID=$(echo ${OUTPUT} | \
|
||||||
grep -oP '(?<=Writing tracing session to: /home/niklas/ROS-Dynamic-Executor-Experiments/analysis/tracing/)[^\s]+')
|
grep -oP '(?<=Writing tracing session to: /home/niklas/ROS-Dynamic-Executor-Experiments/analysis/tracing/)[^\s]+')
|
||||||
|
|
||||||
if [[ -z "$TRACE_ID" ]]; then
|
if [[ -z "$TRACE_ID" ]]; then
|
||||||
|
|
|
@ -26,22 +26,27 @@ option(MULTI_THREADED "Use multi-threading" OFF)
|
||||||
option(USE_TIMER_IN_FUSION_NODES "Use timers in fusion nodes" OFF)
|
option(USE_TIMER_IN_FUSION_NODES "Use timers in fusion nodes" OFF)
|
||||||
|
|
||||||
if(ROS_DEFAULT_EXECUTOR)
|
if(ROS_DEFAULT_EXECUTOR)
|
||||||
|
message(NOTICE "ROS default executor")
|
||||||
add_compile_definitions(ROS_DEFAULT_EXECUTOR)
|
add_compile_definitions(ROS_DEFAULT_EXECUTOR)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
if(EDF_PRIORITY_EXECUTOR)
|
if(EDF_PRIORITY_EXECUTOR)
|
||||||
|
message(NOTICE "EDF executor")
|
||||||
add_compile_definitions(EDF_PRIORITY_EXECUTOR)
|
add_compile_definitions(EDF_PRIORITY_EXECUTOR)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
if(SEMANTIC_EXECUTOR)
|
if(SEMANTIC_EXECUTOR)
|
||||||
|
message(NOTICE "semantic executor")
|
||||||
add_compile_definitions(SEMANTIC_EXECUTOR)
|
add_compile_definitions(SEMANTIC_EXECUTOR)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
if(MULTI_THREADED)
|
if(MULTI_THREADED)
|
||||||
|
message(NOTICE "multi threaded")
|
||||||
add_compile_definitions(MULTI_THREADED)
|
add_compile_definitions(MULTI_THREADED)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
if(USE_TIMER_IN_FUSION_NODES)
|
if(USE_TIMER_IN_FUSION_NODES)
|
||||||
|
message(NOTICE "with timer")
|
||||||
add_compile_definitions(USE_TIMER_IN_FUSION_NODES)
|
add_compile_definitions(USE_TIMER_IN_FUSION_NODES)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
|
|
|
@ -98,8 +98,10 @@ int main(int argc, char **argv)
|
||||||
rclcpp::ExecutorOptions options;
|
rclcpp::ExecutorOptions options;
|
||||||
options.memory_strategy = strategy;
|
options.memory_strategy = strategy;
|
||||||
#ifdef MULTI_THREADED
|
#ifdef MULTI_THREADED
|
||||||
|
std::cout << "multi threaded EDF" << std::endl;
|
||||||
auto executor = priority_executor::MultithreadTimedExecutor(options);
|
auto executor = priority_executor::MultithreadTimedExecutor(options);
|
||||||
#else
|
#else
|
||||||
|
std::cout << "single threaded EDF" << std::endl;
|
||||||
auto executor = priority_executor::TimedExecutor(options);
|
auto executor = priority_executor::TimedExecutor(options);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -108,9 +110,11 @@ int main(int argc, char **argv)
|
||||||
#else // default: ROS
|
#else // default: ROS
|
||||||
#ifdef MULTI_THREADED
|
#ifdef MULTI_THREADED
|
||||||
// Create a multi-threaded executor to handle all nodes
|
// Create a multi-threaded executor to handle all nodes
|
||||||
|
std::cout << "multi threaded ros default" << std::endl;
|
||||||
rclcpp::executors::MultiThreadedExecutor executor;
|
rclcpp::executors::MultiThreadedExecutor executor;
|
||||||
#else
|
#else
|
||||||
// Create a single-threaded executor to handle all nodes
|
// Create a single-threaded executor to handle all nodes
|
||||||
|
std::cout << "single threaded ros default" << std::endl;
|
||||||
rclcpp::executors::SingleThreadedExecutor executor;
|
rclcpp::executors::SingleThreadedExecutor executor;
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -101,6 +101,7 @@ public: \
|
||||||
topic, 10, \
|
topic, 10, \
|
||||||
[this, name](std_msgs::msg::String::SharedPtr msg) \
|
[this, name](std_msgs::msg::String::SharedPtr msg) \
|
||||||
{ \
|
{ \
|
||||||
|
(void) msg; \
|
||||||
}); \
|
}); \
|
||||||
subscriptions_.emplace_back(sub); \
|
subscriptions_.emplace_back(sub); \
|
||||||
} \
|
} \
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue