Skip to content

Commit

Permalink
Merge pull request #1517 from tier4/feature/execution_time
Browse files Browse the repository at this point in the history
  • Loading branch information
HansRobo authored Feb 21, 2025
2 parents d5e558a + d86c9c0 commit 99791bf
Show file tree
Hide file tree
Showing 7 changed files with 321 additions and 38 deletions.
30 changes: 29 additions & 1 deletion .github/workflows/BuildAndRun.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ jobs:
- name: Install sonar-scanner and build-wrapper
uses: sonarsource/sonarcloud-github-c-cpp@v3
env:
SONAR_HOST_URL: ${{ secrets.SONAR_HOST_URL }}
SONAR_HOST_URL: ${{ secrets.SONAR_HOST_URL }}

- name: Build with SonarCloud Build Wrapper
run: |
Expand Down Expand Up @@ -120,6 +120,34 @@ 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
./src/scenario_simulator_v2/.github/workflows/generate_workflow_report.sh /tmp/scenario_workflow/optional_workflow
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> [!NOTE]\n> This is an experimental check and does not block merging the pull-request. \n> But, please be aware that this may indicate a regression.\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
21 changes: 21 additions & 0 deletions .github/workflows/generate_workflow_report.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
#!/bin/sh

if [ $# -ne 1 ]; then
echo "Usage: $0 <workflow_directory>"
exit 1
fi

workflow_directory="$1"
failure_report="$workflow_directory/failure_report.md"
rm -f "$failure_report"

find $workflow_directory -name "result.junit.xml" | while read file; do
[ -e "$file" ] || continue
if grep -q '<failure' "$file"; then
{
echo "<details><summary>scenario failed: $(dirname "${file#"$workflow_directory"/}" | cut -d'/' -f1)</summary><div>\n\n\`\`\`xml"
grep '<failure' "$file"
echo "\`\`\`\n</div></details>\n"
} >> "$failure_report"
fi
done
5 changes: 3 additions & 2 deletions .github/workflows/workflow.sh
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,9 @@ exit_status=0

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
output_directory="/tmp/scenario_workflow/$(basename "$file_path" | sed 's/\.[^.]*$//')/$(basename "$line" | sed 's/\.[^.]*$//')"
ros2 launch scenario_test_runner scenario_test_runner.launch.py scenario:="$line" output_directory:=$output_directory "$@"
ros2 run scenario_test_runner result_checker.py $output_directory/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)"
Expand Down
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/evaluate", rclcpp::QoS(1).transient_local())),
update_time_publisher(create_publisher<tier4_simulation_msgs::msg::UserDefinedValue>(
"/simulation/interpreter/execution_time/update", rclcpp::QoS(1).transient_local())),
output_time_publisher(create_publisher<tier4_simulation_msgs::msg::UserDefinedValue>(
"/simulation/interpreter/execution_time/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", [this]() {
if (std::isnan(evaluateSimulationTime())) {
if (not waiting_for_engagement_to_be_completed and engageable()) {
engage();
Expand All @@ -202,11 +208,44 @@ 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", [this]() { publishCurrentContext(); });

auto generate_double_user_defined_value_message = [](double value) {
tier4_simulation_msgs::msg::UserDefinedValue message;
message.type.data = tier4_simulation_msgs::msg::UserDefinedValueType::DOUBLE;
message.value = std::to_string(value);
return message;
};
evaluate_time_publisher->publish(generate_double_user_defined_value_message(
std::chrono::duration<double>(evaluate_time).count()));
update_time_publisher->publish(generate_double_user_defined_value_message(
std::chrono::duration<double>(update_time).count()));
output_time_publisher->publish(generate_double_user_defined_value_message(
std::chrono::duration<double>(output_time).count()));

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 +288,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 +362,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

0 comments on commit 99791bf

Please sign in to comment.