diff --git a/.github/workflows/BuildAndRun.yaml b/.github/workflows/BuildAndRun.yaml index 1b344986866..b4cef11430e 100644 --- a/.github/workflows/BuildAndRun.yaml +++ b/.github/workflows/BuildAndRun.yaml @@ -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: | @@ -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 "> $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: diff --git a/.github/workflows/generate_workflow_report.sh b/.github/workflows/generate_workflow_report.sh new file mode 100755 index 00000000000..260c565dde3 --- /dev/null +++ b/.github/workflows/generate_workflow_report.sh @@ -0,0 +1,21 @@ +#!/bin/sh + +if [ $# -ne 1 ]; then + echo "Usage: $0 " + 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 'scenario failed: $(dirname "${file#"$workflow_directory"/}" | cut -d'/' -f1)
\n\n\`\`\`xml" + grep '\n" + } >> "$failure_report" + fi +done diff --git a/.github/workflows/workflow.sh b/.github/workflows/workflow.sh index 736b7561e97..2479ae746b6 100755 --- a/.github/workflows/workflow.sh +++ b/.github/workflows/workflow.sh @@ -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)" diff --git a/openscenario/openscenario_interpreter/include/openscenario_interpreter/openscenario_interpreter.hpp b/openscenario/openscenario_interpreter/include/openscenario_interpreter/openscenario_interpreter.hpp index 1fd5a0c67d2..2ec83694855 100644 --- a/openscenario/openscenario_interpreter/include/openscenario_interpreter/openscenario_interpreter.hpp +++ b/openscenario/openscenario_interpreter/include/openscenario_interpreter/openscenario_interpreter.hpp @@ -32,6 +32,7 @@ #include #include #include +#include #include #define INTERPRETER_INFO_STREAM(...) \ @@ -52,6 +53,15 @@ class Interpreter : public rclcpp_lifecycle::LifecycleNode, const rclcpp_lifecycle::LifecyclePublisher::SharedPtr publisher_of_context; + rclcpp_lifecycle::LifecyclePublisher::SharedPtr + evaluate_time_publisher; + + rclcpp_lifecycle::LifecyclePublisher::SharedPtr + update_time_publisher; + + rclcpp_lifecycle::LifecyclePublisher::SharedPtr + output_time_publisher; + double local_frame_rate; double local_real_time_factor; @@ -195,36 +205,6 @@ class Interpreter : public rclcpp_lifecycle::LifecycleNode, return handle(); } } - - template - 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().count() << " or less."); - }; - } }; } // namespace openscenario_interpreter diff --git a/openscenario/openscenario_interpreter/src/openscenario_interpreter.cpp b/openscenario/openscenario_interpreter/src/openscenario_interpreter.cpp index 4cb96beee16..e76840d2d84 100644 --- a/openscenario/openscenario_interpreter/src/openscenario_interpreter.cpp +++ b/openscenario/openscenario_interpreter/src/openscenario_interpreter.cpp @@ -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", rclcpp::QoS(1).transient_local())), + evaluate_time_publisher(create_publisher( + "/simulation/interpreter/execution_time/evaluate", rclcpp::QoS(1).transient_local())), + update_time_publisher(create_publisher( + "/simulation/interpreter/execution_time/update", rclcpp::QoS(1).transient_local())), + output_time_publisher(create_publisher( + "/simulation/interpreter/execution_time/output", rclcpp::QoS(1).transient_local())), local_frame_rate(30), local_real_time_factor(1.0), osc_path(""), @@ -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(); @@ -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(evaluate_time).count())); + update_time_publisher->publish(generate_double_user_defined_value_message( + std::chrono::duration(update_time).count())); + output_time_publisher->publish(generate_double_user_defined_value_message( + std::chrono::duration(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."); + } }); }; @@ -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()); @@ -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("initialize_duration", 30); diff --git a/test_runner/scenario_test_runner/config/optional_workflow.txt b/test_runner/scenario_test_runner/config/optional_workflow.txt new file mode 100644 index 00000000000..10542919b4e --- /dev/null +++ b/test_runner/scenario_test_runner/config/optional_workflow.txt @@ -0,0 +1 @@ +$(find-pkg-share scenario_test_runner)/scenario/execution_time_test.yaml diff --git a/test_runner/scenario_test_runner/scenario/execution_time_test.yaml b/test_runner/scenario_test_runner/scenario/execution_time_test.yaml new file mode 100644 index 00000000000..4b6917f3459 --- /dev/null +++ b/test_runner/scenario_test_runner/scenario/execution_time_test.yaml @@ -0,0 +1,201 @@ +OpenSCENARIO: + FileHeader: + author: 'Kotaro Yoshimoto' + date: '2025-01-28T18:06:53+09:00' + description: 'scenario for execution time test' + revMajor: 1 + revMinor: 3 + ParameterDeclarations: + ParameterDeclaration: [] + CatalogLocations: + VehicleCatalog: + Directory: + path: $(ros2 pkg prefix --share openscenario_experimental_catalog)/vehicle + RoadNetwork: + LogicFile: + filepath: $(ros2 pkg prefix --share kashiwanoha_map)/map + Entities: + ScenarioObject: + - name: Car1 + CatalogReference: &SAMPLE_VEHICLE + catalogName: sample_vehicle + entryName: sample_vehicle + - name: Car2 + CatalogReference: *SAMPLE_VEHICLE + - name: Car3 + CatalogReference: *SAMPLE_VEHICLE + - name: Car4 + CatalogReference: *SAMPLE_VEHICLE + - name: Car5 + CatalogReference: *SAMPLE_VEHICLE + - name: Car6 + CatalogReference: *SAMPLE_VEHICLE + Storyboard: + Init: + Actions: + Private: + - entityRef: Car1 + PrivateAction: + - TeleportAction: + Position: + LanePosition: &DEFAULT_LANE_POSITION + roadId: '' + laneId: 34513 + s: 0 + offset: 0 + Orientation: &DEFAULT_ORIENTATION + type: relative + h: 0 + p: 0 + r: 0 + - entityRef: Car2 + PrivateAction: + - TeleportAction: + Position: + LanePosition: + <<: *DEFAULT_LANE_POSITION + s: 5 + - entityRef: Car3 + PrivateAction: + - TeleportAction: + Position: + LanePosition: + <<: *DEFAULT_LANE_POSITION + s: 10 + - entityRef: Car4 + PrivateAction: + - TeleportAction: + Position: + LanePosition: + <<: *DEFAULT_LANE_POSITION + s: 15 + - entityRef: Car5 + PrivateAction: + - TeleportAction: + Position: + LanePosition: + <<: *DEFAULT_LANE_POSITION + s: 20 + - entityRef: Car6 + PrivateAction: + - TeleportAction: + Position: + LanePosition: + <<: *DEFAULT_LANE_POSITION + s: 25 + Story: + - name: '' + Act: + - name: _EndCondition + ManeuverGroup: + - maximumExecutionCount: 1 + name: '' + Actors: + selectTriggeringEntities: false + EntityRef: + - entityRef: Car1 + Maneuver: + - name: '' + Event: + - name: '' + priority: parallel + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByEntityCondition: + TriggeringEntities: + triggeringEntitiesRule: any + EntityRef: + - entityRef: Car1 + EntityCondition: + ReachPositionCondition: + Position: + LanePosition: + <<: *DEFAULT_LANE_POSITION + s: 40 + tolerance: 0.5 + Action: + - name: '' + UserDefinedAction: + CustomCommandAction: + type: exitSuccess + - name: '' + priority: parallel + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 60 + rule: greaterThan + - Condition: + - name: 'evaluate time checker' + delay: 0 + conditionEdge: none + ByValueCondition: + UserDefinedValueCondition: + name: /simulation/interpreter/execution_time/evaluate + rule: greaterThan + value: 0.001 + - name: 'avoid startup' + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 1 + rule: greaterThan + - Condition: + - name: 'update time checker' + delay: 0 + conditionEdge: none + ByValueCondition: + UserDefinedValueCondition: + name: /simulation/interpreter/execution_time/update + rule: greaterThan + value: 0.005 + - name: 'avoid startup' + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 1 + rule: greaterThan + - Condition: + - name: 'output time checker' + delay: 0 + conditionEdge: none + ByValueCondition: + UserDefinedValueCondition: + name: /simulation/interpreter/execution_time/output + rule: greaterThan + value: 0.001 + - name: 'avoid startup' + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 1 + rule: greaterThan + Action: + - name: '' + UserDefinedAction: + CustomCommandAction: + type: exitFailure + StartTrigger: + ConditionGroup: + - Condition: + - name: '' + delay: 0 + conditionEdge: none + ByValueCondition: + SimulationTimeCondition: + value: 0 + rule: greaterThan + StopTrigger: + ConditionGroup: []