Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add execution time metrics #1517

Open
wants to merge 39 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
39 commits
Select commit Hold shift + click to select a range
c23236c
feat: implement ScopedElapsedTimeRecorder class
HansRobo Jan 28, 2025
b84bae2
feat: record execution time with ScopedElapsedTimeRecorder class
HansRobo Jan 28, 2025
5429178
feat: publish execution time from interpreter
HansRobo Jan 28, 2025
270dc1f
fix: correct time unit conversion
HansRobo Jan 28, 2025
a3c997c
fix: add activate and deactivate process for time publisher in interp…
HansRobo Jan 28, 2025
a484865
feat: add execution_time_test.yaml
HansRobo Jan 28, 2025
a42e4de
refactor: use anchor and aliases in execution_time_test.yaml
HansRobo Jan 28, 2025
017bad1
chore: update threshold for update time in execution_time_test.yaml
HansRobo Jan 28, 2025
a460ab0
Merge branch 'master' into feature/execution_time
HansRobo Jan 28, 2025
5ef2afb
feat: add execution_time_test.yaml into test scenario line-up
HansRobo Jan 28, 2025
fe036f8
fix: correct initialization order
HansRobo Jan 28, 2025
429ec95
refactor: simplify ScopedElapsedTimeRecorder class
HansRobo Jan 28, 2025
a3a3b97
Merge branch 'master' into feature/execution_time
yamacir-kit Jan 30, 2025
60976e7
Merge branch 'master' into feature/execution_time
HansRobo Feb 3, 2025
014bffc
refactor: rename TClock with Clock
HansRobo Feb 4, 2025
4d40bbf
refactor: use ExecutionTimer instead of ScopedElapsedTimeRecorder
HansRobo Feb 5, 2025
e36acb2
refactor: delete unused code
HansRobo Feb 5, 2025
23450f4
fix: delete unavailable include
HansRobo Feb 5, 2025
c7c59ff
chore: move execution_time_test.yaml into optional_workflow.txt
HansRobo Feb 6, 2025
868aae6
chore: change scenario condition for test
HansRobo Feb 6, 2025
2891d3e
feat: create outputs when workflow.sh is executed
HansRobo Feb 6, 2025
4ccc675
feat: add optional workflow execution to BuildAndRun.yaml
HansRobo Feb 6, 2025
75e9908
fix: divide comment step in BuildAndRun.yaml
HansRobo Feb 6, 2025
90e0b6d
Merge branch 'master' into feature/execution_time
HansRobo Feb 6, 2025
8a4bb4b
fix: use comment action
HansRobo Feb 6, 2025
38684cc
fix: correct reading file path
HansRobo Feb 6, 2025
b21f265
fix: set step id to use output correctly
HansRobo Feb 6, 2025
6c8e9e5
fix: handle multiple line output
HansRobo Feb 6, 2025
103f815
fix: use github script to commet file content
HansRobo Feb 7, 2025
8125c23
Merge branch 'master' into feature/execution_time
HansRobo Feb 7, 2025
16f08dc
fix: modify github script
HansRobo Feb 7, 2025
ee00f43
Merge branch 'master' into feature/execution_time
HansRobo Feb 12, 2025
2ad8c6c
chore: simplify failure report
HansRobo Feb 13, 2025
6b3842b
chore: post failure report only when failure scenarios exist
HansRobo Feb 13, 2025
28ddff3
fix: remove const from overwritten variable in github script
HansRobo Feb 13, 2025
34ee822
Merge branch 'master' into feature/execution_time
HansRobo Feb 14, 2025
4177209
Revert "chore: change scenario condition for test"
HansRobo Feb 14, 2025
1b62381
Merge branch 'master' into feature/execution_time
HansRobo Feb 14, 2025
bc38208
Merge branch 'master' into feature/execution_time
HansRobo Feb 14, 2025
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
27 changes: 27 additions & 0 deletions .github/workflows/BuildAndRun.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,33 @@ jobs:
./src/scenario_simulator_v2/.github/workflows/workflow.sh ./src/scenario_simulator_v2/test_runner/scenario_test_runner/config/workflow.txt global_frame_rate:=20
shell: bash

- name: Scenario test (optional)
id: optional-scenario-test
run: |
source install/setup.bash
source install/local_setup.bash
# execute scenarios but ignore the return code
./src/scenario_simulator_v2/.github/workflows/workflow.sh ./src/scenario_simulator_v2/test_runner/scenario_test_runner/config/optional_workflow.txt global_frame_rate:=20 || true
echo failure=$(grep -c "<failure" /tmp/scenario_workflow/optional_workflow/failure_report.md) >> $GITHUB_OUTPUT
shell: bash

- uses: actions/github-script@v7
if: steps.optional-scenario-test.outputs.failure > 0
with:
github-token: ${{ secrets.GITHUB_TOKEN }}
script: |
const fs = require('fs');
let commentBody = fs.readFileSync('/tmp/scenario_workflow/optional_workflow/failure_report.md', 'utf8');
if (commentBody) {
commentBody = '## failure optional scenarios\n' + commentBody;
}
await github.rest.issues.createComment({
issue_number: context.issue.number,
owner: context.repo.owner,
repo: context.repo.repo,
body: commentBody
})

- name: Upload Lcov result
uses: actions/upload-artifact@v4
with:
Expand Down
37 changes: 29 additions & 8 deletions .github/workflows/workflow.sh
Original file line number Diff line number Diff line change
Expand Up @@ -11,17 +11,38 @@ then
exit 1
fi

exit_status=0
workflow_directory="/tmp/scenario_workflow/$(basename "$file_path" | sed 's/\.[^.]*$//')"
rm -rf "$workflow_directory"
mkdir -p "$workflow_directory"

while IFS= read -r line
do
ros2 launch scenario_test_runner scenario_test_runner.launch.py scenario:="$line" "$@"
ros2 run scenario_test_runner result_checker.py /tmp/scenario_test_runner/result.junit.xml
command_exit_status=$?
if [ $command_exit_status -ne 0 ]; then
echo "Error: caught non-zero exit status(code: $command_exit_status)"
exit_status=1
fi

# save the result file before overwriting by next scenario
mkdir -p "$(dirname "$dest_file")"
cp /tmp/scenario_test_runner/result.junit.xml "$workflow_directory/$(basename "$line" | sed 's/\.[^.]*$//').junit.xml"
done < "$file_path"

exit $exit_status
failure_report="$workflow_directory/failure_report.md"
rm -f "$failure_report"
touch "$failure_report"
failure_found=0

for file in "$workflow_directory"/*.junit.xml; do
[ -e "$file" ] || continue
if grep -q '<failure' "$file"; then
failure_found=1
{
echo "<details><summary>scenario failed: $(basename "$file")</summary><div>\n\n\`\`\`xml"
grep '<failure' "$file"
echo "\`\`\`\n</div></details>\n"
} >> "$failure_report"
fi
done

if [ $failure_found -eq 1 ]; then
exit 1
else:
exit 0
fi
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
#include <rclcpp_lifecycle/lifecycle_node.hpp>
#include <scenario_simulator_exception/exception.hpp>
#include <simple_junit/junit5.hpp>
#include <tier4_simulation_msgs/msg/user_defined_value.hpp>
#include <utility>

#define INTERPRETER_INFO_STREAM(...) \
Expand All @@ -52,6 +53,15 @@ class Interpreter : public rclcpp_lifecycle::LifecycleNode,

const rclcpp_lifecycle::LifecyclePublisher<Context>::SharedPtr publisher_of_context;

rclcpp_lifecycle::LifecyclePublisher<tier4_simulation_msgs::msg::UserDefinedValue>::SharedPtr
evaluate_time_publisher;

rclcpp_lifecycle::LifecyclePublisher<tier4_simulation_msgs::msg::UserDefinedValue>::SharedPtr
update_time_publisher;

rclcpp_lifecycle::LifecyclePublisher<tier4_simulation_msgs::msg::UserDefinedValue>::SharedPtr
output_time_publisher;

double local_frame_rate;

double local_real_time_factor;
Expand Down Expand Up @@ -195,36 +205,6 @@ class Interpreter : public rclcpp_lifecycle::LifecycleNode,
return handle();
}
}

template <typename TimeoutHandler, typename Thunk>
auto withTimeoutHandler(TimeoutHandler && handle, Thunk && thunk) -> decltype(auto)
{
if (const auto time = execution_timer.invoke("", thunk); currentLocalFrameRate() < time) {
handle(execution_timer.getStatistics(""));
}
}

auto defaultTimeoutHandler() const
{
/*
Ideally, the scenario should be terminated with an error if the total
time for the ScenarioDefinition evaluation and the traffic_simulator's
updateFrame exceeds the time allowed for a single frame. However, we
have found that many users are in environments where it is not possible
to run the simulator stably at 30 FPS (the default setting) while
running Autoware. In order to prioritize comfortable daily use, we
decided to give up full reproducibility of the scenario and only provide
warnings.
*/

return [this](const auto & statistics) {
RCLCPP_WARN_STREAM(
get_logger(),
"Your machine is not powerful enough to run the scenario at the specified frame rate ("
<< local_frame_rate << " Hz). We recommend that you reduce the frame rate to "
<< 1000.0 / statistics.template max<std::chrono::milliseconds>().count() << " or less.");
};
}
};
} // namespace openscenario_interpreter

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,12 @@ namespace openscenario_interpreter
Interpreter::Interpreter(const rclcpp::NodeOptions & options)
: rclcpp_lifecycle::LifecycleNode("openscenario_interpreter", options),
publisher_of_context(create_publisher<Context>("context", rclcpp::QoS(1).transient_local())),
evaluate_time_publisher(create_publisher<tier4_simulation_msgs::msg::UserDefinedValue>(
"/simulation/interpreter/execution_time_ms/evaluate", rclcpp::QoS(1).transient_local())),
update_time_publisher(create_publisher<tier4_simulation_msgs::msg::UserDefinedValue>(
"/simulation/interpreter/execution_time_ms/update", rclcpp::QoS(1).transient_local())),
output_time_publisher(create_publisher<tier4_simulation_msgs::msg::UserDefinedValue>(
"/simulation/interpreter/execution_time_ms/output", rclcpp::QoS(1).transient_local())),
local_frame_rate(30),
local_real_time_factor(1.0),
osc_path(""),
Expand Down Expand Up @@ -188,7 +194,7 @@ auto Interpreter::on_activate(const rclcpp_lifecycle::State &) -> Result
deactivate();
},
[this]() {
withTimeoutHandler(defaultTimeoutHandler(), [this]() {
const auto evaluate_time = execution_timer.invoke("evaluate", [&]() {
if (std::isnan(evaluateSimulationTime())) {
if (not waiting_for_engagement_to_be_completed and engageable()) {
engage();
Expand All @@ -202,11 +208,41 @@ auto Interpreter::on_activate(const rclcpp_lifecycle::State &) -> Result
} else {
throw Error("No script evaluable.");
}

SimulatorCore::update();

publishCurrentContext();
});

const auto update_time =
execution_timer.invoke("update", [&]() { SimulatorCore::update(); });

const auto output_time =
execution_timer.invoke("output", [&]() { publishCurrentContext(); });

tier4_simulation_msgs::msg::UserDefinedValue msg;
msg.type.data = tier4_simulation_msgs::msg::UserDefinedValueType::DOUBLE;
msg.value =
std::to_string(std::chrono::duration<double, std::milli>(evaluate_time).count());
evaluate_time_publisher->publish(msg);
msg.value = std::to_string(std::chrono::duration<double, std::milli>(update_time).count());
update_time_publisher->publish(msg);
msg.value = std::to_string(std::chrono::duration<double, std::milli>(output_time).count());
output_time_publisher->publish(msg);

if (auto time_until_trigger = timer->time_until_trigger(); time_until_trigger.count() < 0) {
/*
Ideally, the scenario should be terminated with an error if the total
time for the ScenarioDefinition evaluation and the traffic_simulator's
updateFrame exceeds the time allowed for a single frame. However, we
have found that many users are in environments where it is not possible
to run the simulator stably at 30 FPS (the default setting) while
running Autoware. In order to prioritize comfortable daily use, we
decided to give up full reproducibility of the scenario and only provide
warnings.
*/
RCLCPP_WARN_STREAM(
get_logger(),
"Your machine is not powerful enough to run the scenario at the specified frame rate ("
<< local_frame_rate << " Hz). Current frame execution exceeds "
<< -time_until_trigger.count() / 1.e6 << " milliseconds.");
}
});
};

Expand Down Expand Up @@ -249,6 +285,9 @@ auto Interpreter::on_activate(const rclcpp_lifecycle::State &) -> Result
execution_timer.clear();

publisher_of_context->on_activate();
evaluate_time_publisher->on_activate();
update_time_publisher->on_activate();
output_time_publisher->on_activate();

assert(publisher_of_context->is_activated());

Expand Down Expand Up @@ -320,6 +359,15 @@ auto Interpreter::reset() -> void
if (publisher_of_context->is_activated()) {
publisher_of_context->on_deactivate();
}
if (evaluate_time_publisher->is_activated()) {
evaluate_time_publisher->on_deactivate();
}
if (update_time_publisher->is_activated()) {
update_time_publisher->on_deactivate();
}
if (output_time_publisher->is_activated()) {
output_time_publisher->on_deactivate();
}

if (not has_parameter("initialize_duration")) {
declare_parameter<int>("initialize_duration", 30);
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
$(find-pkg-share scenario_test_runner)/scenario/execution_time_test.yaml
Loading
Loading