diff --git a/extension/syntaxes/rscd.tmLanguage.json b/extension/syntaxes/rscd.tmLanguage.json index 7eb44f3..5070922 100644 --- a/extension/syntaxes/rscd.tmLanguage.json +++ b/extension/syntaxes/rscd.tmLanguage.json @@ -28,7 +28,7 @@ }, "keyword": { "name": "keyword.control.rscd", - "match": "\\b(cancel|use|do|integer|none|robot|feedback|action|from|links|state|if|needs|incoming|double|disables|enum|provide|true|object|outgoing|request|import|string|error|interface|default|library|goto|array|datatype|and|value|on|or|initial|false|requirement|message|transition|with|component|boolean|service|response|variable|behaviour|to)\\b" + "match": "\\b(cancel|use|do|integer|none|robot|feedback|action|from|links|state|if|needs|incoming|double|disables|enum|provide|true|object|outgoing|request|import|string|error|interface|default|library|goto|array|datatype|and|value|on|or|initial|marked|false|requirement|message|transition|with|component|boolean|service|response|variable|behaviour|to)\\b" } }, "patterns": [ diff --git a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/CorrectResultTypeRuleTest.xtend b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/CorrectResultTypeRuleTest.xtend index d9b1a10..7576a16 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/CorrectResultTypeRuleTest.xtend +++ b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/CorrectResultTypeRuleTest.xtend @@ -29,7 +29,7 @@ class CorrectResultTypeRuleTest { service test_service with request: boolean, response: boolean links unit behaviour { - initial state idle { + initial marked state idle { on request to test_message on request to test_service on response from test_service @@ -51,7 +51,7 @@ class CorrectResultTypeRuleTest { service test_service with request: boolean, response: boolean links unit behaviour { - initial state idle { + initial marked state idle { on feedback from test_service } } @@ -74,7 +74,7 @@ class CorrectResultTypeRuleTest { service test_service with request: boolean, response: boolean links unit behaviour { - initial state idle { + initial marked state idle { on request to test_message } } @@ -97,7 +97,7 @@ class CorrectResultTypeRuleTest { service test_service with request: boolean, response: boolean links unit behaviour { - initial state idle { + initial marked state idle { on response to test_message } } diff --git a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/IntegerRangeRequiredRuleTest.xtend b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/IntegerRangeRequiredRuleTest.xtend index d7e3cbb..6b61e3c 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/IntegerRangeRequiredRuleTest.xtend +++ b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/IntegerRangeRequiredRuleTest.xtend @@ -29,7 +29,7 @@ class IntegerRangeRequiredRuleTest { behaviour { variable current_distance: integer(0..20) = 0 - initial state idle { + initial marked state idle { on response from distance do current_distance := value } } @@ -50,7 +50,7 @@ class IntegerRangeRequiredRuleTest { behaviour { variable current_distance: integer = 0 - initial state idle { + initial marked state idle { on response from distance do current_distance := value } } @@ -74,7 +74,7 @@ class IntegerRangeRequiredRuleTest { behaviour { variable current_distance: integer(0..20) = 0 - initial state idle { + initial marked state idle { on response from distance do current_distance := value } } @@ -102,7 +102,7 @@ class IntegerRangeRequiredRuleTest { behaviour { variable current_distance: integer(0..20) = 0 - initial state idle { + initial marked state idle { on response from distance do current_distance := value.distance } } diff --git a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/InterfaceLinkRequiredRuleTest.xtend b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/InterfaceLinkRequiredRuleTest.xtend index a7556bf..6301145 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/InterfaceLinkRequiredRuleTest.xtend +++ b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/InterfaceLinkRequiredRuleTest.xtend @@ -32,7 +32,7 @@ class InterfaceLinkRequiredRuleTest { outgoing message distance with type: Complex links test behaviour { - initial state idle {} + initial marked state idle {} } } } @@ -51,7 +51,7 @@ class InterfaceLinkRequiredRuleTest { outgoing message distance with type: Complex behaviour { - initial state idle {} + initial marked state idle {} } } } diff --git a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/MarkedStateRuleTest.xtend b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/MarkedStateRuleTest.xtend new file mode 100644 index 0000000..468e956 --- /dev/null +++ b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/MarkedStateRuleTest.xtend @@ -0,0 +1,49 @@ +package nl.tue.robotsupervisorycontrollerdsl.tests.validation.rules + +import com.google.inject.Inject +import org.eclipse.xtext.testing.InjectWith +import org.eclipse.xtext.testing.extensions.InjectionExtension +import org.eclipse.xtext.testing.util.ParseHelper +import org.junit.jupiter.api.Test +import org.junit.jupiter.api.^extension.ExtendWith +import nl.tue.robotsupervisorycontrollerdsl.robotSupervisoryControllerDSL.Base +import nl.tue.robotsupervisorycontrollerdsl.tests.RobotSupervisoryControllerDSLInjectorProvider +import org.eclipse.xtext.testing.validation.ValidationTestHelper +import nl.tue.robotsupervisorycontrollerdsl.robotSupervisoryControllerDSL.RobotSupervisoryControllerDSLPackage +import nl.tue.robotsupervisorycontrollerdsl.validation.rules.MarkedStateRule + +@ExtendWith(InjectionExtension) +@InjectWith(RobotSupervisoryControllerDSLInjectorProvider) +class MarkedStateRuleTest { + @Inject extension ParseHelper + @Inject extension ValidationTestHelper + + @Test + def void checkValid() { + " + robot UnitTestRobot { + component Component { + behaviour { + initial marked state idle {} + } + } + } + ".parse.assertNoErrors + } + + @Test + def void checkNoMarkedState() { + " + robot UnitTestRobot { + component Component { + behaviour { + initial state idle {} + } + } + } + ".parse.assertError( + RobotSupervisoryControllerDSLPackage.Literals.AUTOMATON, + MarkedStateRule.NO_MARKED_STATE + ) + } +} diff --git a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/NoAssignmentOnMessagesToNodeRuleTest.xtend b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/NoAssignmentOnMessagesToNodeRuleTest.xtend index 4d79e9f..cb37b58 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/NoAssignmentOnMessagesToNodeRuleTest.xtend +++ b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/NoAssignmentOnMessagesToNodeRuleTest.xtend @@ -28,7 +28,7 @@ class NoAssignmentOnMessagesToNodeRuleTest { behaviour { variable result: boolean = false - initial state idle { + initial marked state idle { on response from test_message do result := value } } @@ -47,7 +47,7 @@ class NoAssignmentOnMessagesToNodeRuleTest { behaviour { variable result: boolean = false - initial state idle { + initial marked state idle { on request to test_message do result := value } } diff --git a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/NoAssignmentOutsideScopeRuleTest.xtend b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/NoAssignmentOutsideScopeRuleTest.xtend index b77fb93..68631a2 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/NoAssignmentOutsideScopeRuleTest.xtend +++ b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/NoAssignmentOutsideScopeRuleTest.xtend @@ -28,7 +28,7 @@ class NoAssignmentOutsideScopeRuleTest { behaviour { variable result: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result := value } } @@ -40,7 +40,7 @@ class NoAssignmentOutsideScopeRuleTest { behaviour { variable result: boolean = false - initial state idle { + initial marked state idle { on response from test_message_two do result := value } } @@ -59,7 +59,7 @@ class NoAssignmentOutsideScopeRuleTest { behaviour { variable result: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do Component2.result := value } } @@ -71,7 +71,7 @@ class NoAssignmentOutsideScopeRuleTest { behaviour { variable result: boolean = false - initial state idle { + initial marked state idle { on response from test_message_two do Component1.result := value } } diff --git a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/SingleComponentBehaviourRuleTest.xtend b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/SingleComponentBehaviourRuleTest.xtend index 7419dcb..1d486e3 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/SingleComponentBehaviourRuleTest.xtend +++ b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/SingleComponentBehaviourRuleTest.xtend @@ -24,7 +24,7 @@ class SingleComponentBehaviourRuleTest { robot UnitTestRobot { component Component { behaviour { - initial state idle {} + initial marked state idle {} } } } @@ -37,11 +37,11 @@ class SingleComponentBehaviourRuleTest { robot UnitTestRobot { component Component { behaviour { - initial state idle {} + initial marked state idle {} } behaviour { - initial state idle {} + initial marked state idle {} } } } diff --git a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/SingleInitialStateRuleTest.xtend b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/SingleInitialStateRuleTest.xtend index 667a161..0cbe2aa 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/SingleInitialStateRuleTest.xtend +++ b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/SingleInitialStateRuleTest.xtend @@ -24,7 +24,7 @@ class SingleInitialStateRuleTest { robot UnitTestRobot { component Component { behaviour { - initial state idle {} + initial marked state idle {} } } } @@ -37,8 +37,8 @@ class SingleInitialStateRuleTest { robot UnitTestRobot { component Component { behaviour { - initial state idle {} - initial state start {} + initial marked state idle {} + initial marked state start {} } } } @@ -54,6 +54,7 @@ class SingleInitialStateRuleTest { robot UnitTestRobot { component Component { behaviour { + marked state test {} } } } diff --git a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/TypeCheckRuleTest.xtend b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/TypeCheckRuleTest.xtend index e0e25fe..b0c7396 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/TypeCheckRuleTest.xtend +++ b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/TypeCheckRuleTest.xtend @@ -38,7 +38,7 @@ class TypeCheckRuleTest { variable result_double: double variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_boolean := true or false on response from test_message_one do result_boolean := true and false on response from test_message_one do result_boolean := 5 > 0 @@ -74,7 +74,7 @@ class TypeCheckRuleTest { variable result_integer: integer(0..20) = 0 variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_boolean := true or 1 } } @@ -97,7 +97,7 @@ class TypeCheckRuleTest { variable result_integer: integer(0..20) = 0 variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_boolean := true and 1 } } @@ -120,7 +120,7 @@ class TypeCheckRuleTest { variable result_integer: integer(0..20) = 0 variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_boolean := 5 > true } } @@ -143,7 +143,7 @@ class TypeCheckRuleTest { variable result_integer: integer(0..20) = 0 variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_boolean := 5 < true } } @@ -166,7 +166,7 @@ class TypeCheckRuleTest { variable result_integer: integer(0..20) = 0 variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_boolean := 5 >= true } } @@ -189,7 +189,7 @@ class TypeCheckRuleTest { variable result_integer: integer(0..20) = 0 variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_boolean := 5 <= true } } @@ -212,7 +212,7 @@ class TypeCheckRuleTest { variable result_integer: integer(0..20) = 0 variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_boolean := !5 } } @@ -235,7 +235,7 @@ class TypeCheckRuleTest { variable result_integer: integer(0..20) = 0 variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_integer := -true } } @@ -258,7 +258,7 @@ class TypeCheckRuleTest { variable result_integer: integer(0..20) = 0 variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_integer := 5 * true } } @@ -281,7 +281,7 @@ class TypeCheckRuleTest { variable result_integer: integer(0..20) = 0 variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_integer := 5 / true } } @@ -304,7 +304,7 @@ class TypeCheckRuleTest { variable result_integer: integer(0..20) = 0 variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_integer := 5 + true } } @@ -327,7 +327,7 @@ class TypeCheckRuleTest { variable result_integer: integer(0..20) = 0 variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_integer := 5 - true } } @@ -350,7 +350,7 @@ class TypeCheckRuleTest { variable result_integer: integer(0..20) = 0 variable result_boolean: boolean = false - initial state idle { + initial marked state idle { transition if 5 } } @@ -410,7 +410,7 @@ class TypeCheckRuleTest { behaviour { variable result_boolean: boolean = false - initial state idle { + initial marked state idle { on response from test_message_one do result_boolean := 5 } } @@ -430,7 +430,7 @@ class TypeCheckRuleTest { behaviour { variable result_boolean: boolean = 0 - initial state idle {} + initial marked state idle {} } } } diff --git a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/UniqueStateNameRuleTest.xtend b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/UniqueStateNameRuleTest.xtend index d1b045b..9097e84 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/UniqueStateNameRuleTest.xtend +++ b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/UniqueStateNameRuleTest.xtend @@ -24,7 +24,7 @@ class UniqueStateNameRuleTest { robot UnitTestRobot { component Component1 { behaviour { - initial state one {} + initial marked state one {} state two {} } } @@ -38,7 +38,7 @@ class UniqueStateNameRuleTest { robot UnitTestRobot { component Component1 { behaviour { - initial state one {} + initial marked state one {} state one {} } } diff --git a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/UniqueVariableNameRuleTest.xtend b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/UniqueVariableNameRuleTest.xtend index 54b56f2..1b37e8b 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/UniqueVariableNameRuleTest.xtend +++ b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/UniqueVariableNameRuleTest.xtend @@ -26,7 +26,7 @@ class UniqueVariableNameRuleTest { behaviour { variable one: boolean = false variable two: boolean = false - initial state one {} + initial marked state one {} } } } @@ -42,7 +42,7 @@ class UniqueVariableNameRuleTest { variable one: boolean = false variable one: boolean = false - initial state one {} + initial marked state one {} } } } diff --git a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/UsedDataTypeRuleTest.xtend b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/UsedDataTypeRuleTest.xtend index ff1fecc..b03c69f 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/UsedDataTypeRuleTest.xtend +++ b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/UsedDataTypeRuleTest.xtend @@ -36,7 +36,7 @@ class UsedDataTypeRuleTest { variable result_string: string = \"\" variable result_double: double = 0.0 - initial state idle {} + initial marked state idle {} } } } @@ -54,7 +54,7 @@ class UsedDataTypeRuleTest { behaviour { variable result: boolean - initial state idle {} + initial marked state idle {} } } } @@ -75,7 +75,7 @@ class UsedDataTypeRuleTest { behaviour { variable result: array(boolean) - initial state idle {} + initial marked state idle {} } } } @@ -98,7 +98,7 @@ class UsedDataTypeRuleTest { variable result_string: string = \"\" variable result_double: double = 0.0 - initial state idle { + initial marked state idle { transition if result_string = \"\" goto idle } } @@ -123,7 +123,7 @@ class UsedDataTypeRuleTest { variable result_string: string = \"\" variable result_double: double = 0.0 - initial state idle { + initial marked state idle { transition if result_double > 0.0 goto idle } } diff --git a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/ValidEnumValueRuleTest.xtend b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/ValidEnumValueRuleTest.xtend index 36e30ab..b3d8fab 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/ValidEnumValueRuleTest.xtend +++ b/language/nl.tue.robotsupervisorycontrollerdsl.tests/src/nl/tue/robotsupervisorycontrollerdsl/tests/validation/rules/ValidEnumValueRuleTest.xtend @@ -29,7 +29,7 @@ class ValidEnumValueRuleTest { component Component1 { behaviour { - initial state unique {} + initial marked state unique {} } } } @@ -47,7 +47,7 @@ class ValidEnumValueRuleTest { component Component1 { behaviour { - initial state positive {} + initial marked state positive {} } } } diff --git a/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/RobotSupervisoryControllerDSL.xtext b/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/RobotSupervisoryControllerDSL.xtext index 9435475..b6e5a6d 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/RobotSupervisoryControllerDSL.xtext +++ b/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/RobotSupervisoryControllerDSL.xtext @@ -130,7 +130,7 @@ Transition: ResultTransition | TauTransition; State: - {State} (initial?='initial')? 'state' name=ID '{' + {State} (initial?='initial')? (marked?='marked')? 'state' name=ID '{' (transitions+=Transition)* '}'; diff --git a/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/generator/cif/automaton/AutomatonGenerator.xtend b/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/generator/cif/automaton/AutomatonGenerator.xtend index de3df66..b23eaa5 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/generator/cif/automaton/AutomatonGenerator.xtend +++ b/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/generator/cif/automaton/AutomatonGenerator.xtend @@ -107,7 +107,7 @@ class AutomatonGenerator { private def compile(State state, Robot robot, Automaton automaton) ''' location «state.name»: - «IF state.initial»initial;«ENDIF» marked; + «IF state.initial»initial;«ENDIF» «IF state.marked»marked;«ENDIF» «robot.allowUncontrollableEvents(automaton, state)» diff --git a/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/validation/RobotSupervisoryControllerDSLValidator.java b/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/validation/RobotSupervisoryControllerDSLValidator.java index 5bce422..82ce86d 100644 --- a/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/validation/RobotSupervisoryControllerDSLValidator.java +++ b/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/validation/RobotSupervisoryControllerDSLValidator.java @@ -6,6 +6,7 @@ import nl.tue.robotsupervisorycontrollerdsl.validation.rules.CorrectResultTypeRule; import nl.tue.robotsupervisorycontrollerdsl.validation.rules.IntegerRangeRequiredRule; import nl.tue.robotsupervisorycontrollerdsl.validation.rules.InterfaceLinkRequiredRule; +import nl.tue.robotsupervisorycontrollerdsl.validation.rules.MarkedStateRule; import nl.tue.robotsupervisorycontrollerdsl.validation.rules.NoAssignmentOnMessagesToNodeRule; import nl.tue.robotsupervisorycontrollerdsl.validation.rules.NoAssignmentOutsideScopeRule; import nl.tue.robotsupervisorycontrollerdsl.validation.rules.SingleComponentBehaviourRule; @@ -42,6 +43,7 @@ UniquePropertyNameRule.class, UniqueVariableNameRule.class, ValidEnumValueRule.class, + MarkedStateRule.class, }) public class RobotSupervisoryControllerDSLValidator extends AbstractRobotSupervisoryControllerDSLValidator { } diff --git a/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/validation/rules/MarkedStateRule.java b/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/validation/rules/MarkedStateRule.java new file mode 100644 index 0000000..bd86afd --- /dev/null +++ b/language/nl.tue.robotsupervisorycontrollerdsl/src/nl/tue/robotsupervisorycontrollerdsl/validation/rules/MarkedStateRule.java @@ -0,0 +1,31 @@ +package nl.tue.robotsupervisorycontrollerdsl.validation.rules; + +import java.util.List; +import java.util.stream.Collectors; + +import org.eclipse.xtext.validation.Check; + +import nl.tue.robotsupervisorycontrollerdsl.robotSupervisoryControllerDSL.Automaton; +import nl.tue.robotsupervisorycontrollerdsl.robotSupervisoryControllerDSL.RobotSupervisoryControllerDSLPackage; +import nl.tue.robotsupervisorycontrollerdsl.validation.common.AbstractValidationRule; + +public class MarkedStateRule extends AbstractValidationRule { + public static final String NO_MARKED_STATE = "noMarkedState"; + + @Check + public void checkMarkedState(Automaton entity) { + List initialStates = entity + .getDefinitions() + .stream() + .filter(definition -> definition instanceof nl.tue.robotsupervisorycontrollerdsl.robotSupervisoryControllerDSL.State) + .map(definition -> (nl.tue.robotsupervisorycontrollerdsl.robotSupervisoryControllerDSL.State) definition) + .filter(state -> state.isMarked()) + .collect(Collectors.toList()); + + if (initialStates.isEmpty()) { + error("An automaton should have at least a marked state.", + RobotSupervisoryControllerDSLPackage.Literals.AUTOMATON__DEFINITIONS, + NO_MARKED_STATE); + } + } +} diff --git a/scenarios/scenario-1-line-follower/controller/include/controller/controller_engine.c b/scenarios/scenario-1-line-follower/controller/include/controller/controller_engine.c index 01adcaa..442eb15 100644 --- a/scenarios/scenario-1-line-follower/controller/include/controller/controller_engine.c +++ b/scenarios/scenario-1-line-follower/controller/include/controller/controller_engine.c @@ -39,8 +39,8 @@ const char *controller_event_names[] = { "data_correction.c_none", /**< Event data_correction.c_none. */ "message_no_line.u_response", /**< Event message_no_line.u_response. */ "data_no_line.c_none", /**< Event data_no_line.c_none. */ - "component_LidarSensor.c_pL5GUHQARUVYQ", /**< Event component_LidarSensor.c_pL5GUHQARUVYQ. */ - "component_LidarSensor.c_pOTNR1GAQDAZE", /**< Event component_LidarSensor.c_pOTNR1GAQDAZE. */ + "component_LidarSensor.c_pVF9ZLWJF9HHG", /**< Event component_LidarSensor.c_pVF9ZLWJF9HHG. */ + "component_LidarSensor.c_pIBXNH5R0L1DS", /**< Event component_LidarSensor.c_pIBXNH5R0L1DS. */ "message_scan.u_response", /**< Event message_scan.u_response. */ "data_scan.c_none", /**< Event data_scan.c_none. */ "message_stop.u_response", /**< Event message_stop.u_response. */ @@ -49,16 +49,16 @@ const char *controller_event_names[] = { "data_continue.c_none", /**< Event data_continue.c_none. */ "message_move.c_trigger", /**< Event message_move.c_trigger. */ "data_move.c_none", /**< Event data_move.c_none. */ - "data_move.c_p1FV6MKBBH2L7", /**< Event data_move.c_p1FV6MKBBH2L7. */ + "data_move.c_pLLL4DHRWZ0J5", /**< Event data_move.c_pLLL4DHRWZ0J5. */ "message_halt.c_trigger", /**< Event message_halt.c_trigger. */ "data_halt.c_none", /**< Event data_halt.c_none. */ - "data_halt.c_pRJCB2BDWXUOW", /**< Event data_halt.c_pRJCB2BDWXUOW. */ + "data_halt.c_p6PLB4ODMJIWE", /**< Event data_halt.c_p6PLB4ODMJIWE. */ }; /** Enumeration names. */ const char *enum_names[] = { - "data_p1KKXDLC4H55M", - "data_p1UWHO5NYF84Z", + "data_p8V5D37XULD3A", + "data_pX6JOW6V7BDK7", "in_service", "line_found", "no_line", @@ -103,43 +103,43 @@ static void PrintOutput(controller_Event_ event, BoolType pre) { /* Event execution code. */ /** - * Execute code for event "component_LidarSensor.c_pL5GUHQARUVYQ". + * Execute code for event "component_LidarSensor.c_pIBXNH5R0L1DS". * * @return Whether the event was performed. */ static BoolType execEvent0(void) { - BoolType guard = ((component_LidarSensor_) == (_controller_unsafe_distance)) && ((component_LidarSensor_v_current_distance_) == (_controller_safe)); + BoolType guard = ((component_LidarSensor_) == (_controller_safe_distance)) && ((component_LidarSensor_v_current_distance_) == (_controller_unsafe)); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(component_LidarSensor_c_pL5GUHQARUVYQ_, TRUE); + controller_InfoEvent(component_LidarSensor_c_pIBXNH5R0L1DS_, TRUE); #endif - component_LidarSensor_ = _controller_safe_distance; + component_LidarSensor_ = _controller_unsafe_distance; #if EVENT_OUTPUT - controller_InfoEvent(component_LidarSensor_c_pL5GUHQARUVYQ_, FALSE); + controller_InfoEvent(component_LidarSensor_c_pIBXNH5R0L1DS_, FALSE); #endif return TRUE; } /** - * Execute code for event "component_LidarSensor.c_pOTNR1GAQDAZE". + * Execute code for event "component_LidarSensor.c_pVF9ZLWJF9HHG". * * @return Whether the event was performed. */ static BoolType execEvent1(void) { - BoolType guard = ((component_LidarSensor_) == (_controller_safe_distance)) && ((component_LidarSensor_v_current_distance_) == (_controller_unsafe)); + BoolType guard = ((component_LidarSensor_) == (_controller_unsafe_distance)) && ((component_LidarSensor_v_current_distance_) == (_controller_safe)); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(component_LidarSensor_c_pOTNR1GAQDAZE_, TRUE); + controller_InfoEvent(component_LidarSensor_c_pVF9ZLWJF9HHG_, TRUE); #endif - component_LidarSensor_ = _controller_unsafe_distance; + component_LidarSensor_ = _controller_safe_distance; #if EVENT_OUTPUT - controller_InfoEvent(component_LidarSensor_c_pOTNR1GAQDAZE_, FALSE); + controller_InfoEvent(component_LidarSensor_c_pVF9ZLWJF9HHG_, FALSE); #endif return TRUE; } @@ -202,26 +202,26 @@ static BoolType execEvent4(void) { } /** - * Execute code for event "data_halt.c_pRJCB2BDWXUOW". + * Execute code for event "data_halt.c_p6PLB4ODMJIWE". * * @return Whether the event was performed. */ static BoolType execEvent5(void) { - BoolType guard = ((data_halt_) == (_controller_none)) || ((data_halt_) == (_controller_data_p1UWHO5NYF84Z)); + BoolType guard = ((data_halt_) == (_controller_none)) || ((data_halt_) == (_controller_data_p8V5D37XULD3A)); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_halt_c_pRJCB2BDWXUOW_, TRUE); + controller_InfoEvent(data_halt_c_p6PLB4ODMJIWE_, TRUE); #endif if ((data_halt_) == (_controller_none)) { - data_halt_ = _controller_data_p1UWHO5NYF84Z; - } else if ((data_halt_) == (_controller_data_p1UWHO5NYF84Z)) { - data_halt_ = _controller_data_p1UWHO5NYF84Z; + data_halt_ = _controller_data_p8V5D37XULD3A; + } else if ((data_halt_) == (_controller_data_p8V5D37XULD3A)) { + data_halt_ = _controller_data_p8V5D37XULD3A; } #if EVENT_OUTPUT - controller_InfoEvent(data_halt_c_pRJCB2BDWXUOW_, FALSE); + controller_InfoEvent(data_halt_c_p6PLB4ODMJIWE_, FALSE); #endif return TRUE; } @@ -252,26 +252,26 @@ static BoolType execEvent6(void) { } /** - * Execute code for event "data_move.c_p1FV6MKBBH2L7". + * Execute code for event "data_move.c_pLLL4DHRWZ0J5". * * @return Whether the event was performed. */ static BoolType execEvent7(void) { - BoolType guard = ((data_move_) == (_controller_none)) || ((data_move_) == (_controller_data_p1KKXDLC4H55M)); + BoolType guard = ((data_move_) == (_controller_none)) || ((data_move_) == (_controller_data_pX6JOW6V7BDK7)); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_p1FV6MKBBH2L7_, TRUE); + controller_InfoEvent(data_move_c_pLLL4DHRWZ0J5_, TRUE); #endif if ((data_move_) == (_controller_none)) { - data_move_ = _controller_data_p1KKXDLC4H55M; - } else if ((data_move_) == (_controller_data_p1KKXDLC4H55M)) { - data_move_ = _controller_data_p1KKXDLC4H55M; + data_move_ = _controller_data_pX6JOW6V7BDK7; + } else if ((data_move_) == (_controller_data_pX6JOW6V7BDK7)) { + data_move_ = _controller_data_pX6JOW6V7BDK7; } #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_p1FV6MKBBH2L7_, FALSE); + controller_InfoEvent(data_move_c_pLLL4DHRWZ0J5_, FALSE); #endif return TRUE; } @@ -525,14 +525,14 @@ static void PerformEvents(void) { break; } - if (execEvent0()) continue; /* (Try to) perform event "component_LidarSensor.c_pL5GUHQARUVYQ". */ - if (execEvent1()) continue; /* (Try to) perform event "component_LidarSensor.c_pOTNR1GAQDAZE". */ + if (execEvent0()) continue; /* (Try to) perform event "component_LidarSensor.c_pIBXNH5R0L1DS". */ + if (execEvent1()) continue; /* (Try to) perform event "component_LidarSensor.c_pVF9ZLWJF9HHG". */ if (execEvent2()) continue; /* (Try to) perform event "data_continue.c_none". */ if (execEvent3()) continue; /* (Try to) perform event "data_correction.c_none". */ if (execEvent4()) continue; /* (Try to) perform event "data_halt.c_none". */ - if (execEvent5()) continue; /* (Try to) perform event "data_halt.c_pRJCB2BDWXUOW". */ + if (execEvent5()) continue; /* (Try to) perform event "data_halt.c_p6PLB4ODMJIWE". */ if (execEvent6()) continue; /* (Try to) perform event "data_move.c_none". */ - if (execEvent7()) continue; /* (Try to) perform event "data_move.c_p1FV6MKBBH2L7". */ + if (execEvent7()) continue; /* (Try to) perform event "data_move.c_pLLL4DHRWZ0J5". */ if (execEvent8()) continue; /* (Try to) perform event "data_no_line.c_none". */ if (execEvent9()) continue; /* (Try to) perform event "data_scan.c_none". */ if (execEvent10()) continue; /* (Try to) perform event "data_stop.c_none". */ @@ -602,9 +602,9 @@ void controller_EngineTimeStep(double delta) { */ BoolType controller_EnginePerformEvent(controller_Event_ event) { switch (event) { - case component_LidarSensor_c_pL5GUHQARUVYQ_: + case component_LidarSensor_c_pIBXNH5R0L1DS_: return execEvent0(); - case component_LidarSensor_c_pOTNR1GAQDAZE_: + case component_LidarSensor_c_pVF9ZLWJF9HHG_: return execEvent1(); case data_continue_c_none_: return execEvent2(); @@ -612,11 +612,11 @@ BoolType controller_EnginePerformEvent(controller_Event_ event) { return execEvent3(); case data_halt_c_none_: return execEvent4(); - case data_halt_c_pRJCB2BDWXUOW_: + case data_halt_c_p6PLB4ODMJIWE_: return execEvent5(); case data_move_c_none_: return execEvent6(); - case data_move_c_p1FV6MKBBH2L7_: + case data_move_c_pLLL4DHRWZ0J5_: return execEvent7(); case data_no_line_c_none_: return execEvent8(); diff --git a/scenarios/scenario-1-line-follower/controller/include/controller/controller_engine.h b/scenarios/scenario-1-line-follower/controller/include/controller/controller_engine.h index 2327c80..e6e1d94 100644 --- a/scenarios/scenario-1-line-follower/controller/include/controller/controller_engine.h +++ b/scenarios/scenario-1-line-follower/controller/include/controller/controller_engine.h @@ -11,8 +11,8 @@ * Note that integer ranges are ignored in C. */ enum Enumcontroller_ { - _controller_data_p1KKXDLC4H55M, - _controller_data_p1UWHO5NYF84Z, + _controller_data_p8V5D37XULD3A, + _controller_data_pX6JOW6V7BDK7, _controller_in_service, _controller_line_found, _controller_no_line, @@ -38,8 +38,8 @@ enum controllerEventEnum_ { data_correction_c_none_, /**< Event data_correction.c_none. */ message_no_line_u_response_, /**< Event message_no_line.u_response. */ data_no_line_c_none_, /**< Event data_no_line.c_none. */ - component_LidarSensor_c_pL5GUHQARUVYQ_, /**< Event component_LidarSensor.c_pL5GUHQARUVYQ. */ - component_LidarSensor_c_pOTNR1GAQDAZE_, /**< Event component_LidarSensor.c_pOTNR1GAQDAZE. */ + component_LidarSensor_c_pVF9ZLWJF9HHG_, /**< Event component_LidarSensor.c_pVF9ZLWJF9HHG. */ + component_LidarSensor_c_pIBXNH5R0L1DS_, /**< Event component_LidarSensor.c_pIBXNH5R0L1DS. */ message_scan_u_response_, /**< Event message_scan.u_response. */ data_scan_c_none_, /**< Event data_scan.c_none. */ message_stop_u_response_, /**< Event message_stop.u_response. */ @@ -48,10 +48,10 @@ enum controllerEventEnum_ { data_continue_c_none_, /**< Event data_continue.c_none. */ message_move_c_trigger_, /**< Event message_move.c_trigger. */ data_move_c_none_, /**< Event data_move.c_none. */ - data_move_c_p1FV6MKBBH2L7_, /**< Event data_move.c_p1FV6MKBBH2L7. */ + data_move_c_pLLL4DHRWZ0J5_, /**< Event data_move.c_pLLL4DHRWZ0J5. */ message_halt_c_trigger_, /**< Event message_halt.c_trigger. */ data_halt_c_none_, /**< Event data_halt.c_none. */ - data_halt_c_pRJCB2BDWXUOW_, /**< Event data_halt.c_pRJCB2BDWXUOW. */ + data_halt_c_p6PLB4ODMJIWE_, /**< Event data_halt.c_p6PLB4ODMJIWE. */ }; typedef enum controllerEventEnum_ controller_Event_; diff --git a/scenarios/scenario-1-line-follower/controller/src/member_function.cpp b/scenarios/scenario-1-line-follower/controller/src/member_function.cpp index 0dd2f57..b7a610c 100644 --- a/scenarios/scenario-1-line-follower/controller/src/member_function.cpp +++ b/scenarios/scenario-1-line-follower/controller/src/member_function.cpp @@ -163,7 +163,7 @@ class Controller : public rclcpp::Node { void call_message_move() { auto value = geometry_msgs::msg::Twist(); - if (data_move_ == _controller_data_p1KKXDLC4H55M) { + if (data_move_ == _controller_data_pX6JOW6V7BDK7) { value.linear.x = 0.6; value.angular.z = (-code_LineDetector_current_correction) / 100; } @@ -176,7 +176,7 @@ class Controller : public rclcpp::Node { void call_message_halt() { auto value = geometry_msgs::msg::Twist(); - if (data_halt_ == _controller_data_p1UWHO5NYF84Z) { + if (data_halt_ == _controller_data_p8V5D37XULD3A) { value.linear.x = 0.0; value.angular.z = 0.0; } @@ -216,7 +216,7 @@ class Controller : public rclcpp::Node { output << "}"; output << "},"; output << "\"transitions\": " << serialize_json_vector(taken_transitions) << ","; - output << "\"definition\": " << "{\"name\":\"LineFollowerController\",\"components\":[{\"name\":\"LineDetector\",\"messages\":[\"correction\",\"no_line\"],\"services\":[],\"actions\":[],\"behaviour\":{\"variables\":[\"current_correction\"],\"states\":[{\"name\":\"no_line\",\"initial\":true,\"transitions\":[{\"next\":\"line_found\",\"id\":\"message_correction_u_response_\",\"type\":\"response\",\"communication\":\"correction\"}]},{\"name\":\"line_found\",\"initial\":false,\"transitions\":[{\"next\":\"no_line\",\"id\":\"message_no_line_u_response_\",\"type\":\"response\",\"communication\":\"no_line\"},{\"next\":null,\"id\":\"message_correction_u_response_\",\"type\":\"response\",\"communication\":\"correction\"}]}]}},{\"name\":\"LidarSensor\",\"messages\":[\"scan\"],\"services\":[],\"actions\":[],\"behaviour\":{\"variables\":[\"current_distance\"],\"states\":[{\"name\":\"unsafe_distance\",\"initial\":true,\"transitions\":[{\"next\":\"safe_distance\",\"id\":\"component_LidarSensor_c_pL5GUHQARUVYQ_\",\"type\":\"tau\"},{\"next\":null,\"id\":\"message_scan_u_response_\",\"type\":\"response\",\"communication\":\"scan\"}]},{\"name\":\"safe_distance\",\"initial\":false,\"transitions\":[{\"next\":\"unsafe_distance\",\"id\":\"component_LidarSensor_c_pOTNR1GAQDAZE_\",\"type\":\"tau\"},{\"next\":null,\"id\":\"message_scan_u_response_\",\"type\":\"response\",\"communication\":\"scan\"}]}]}},{\"name\":\"EmergencyStop\",\"messages\":[\"stop\",\"continue\"],\"services\":[],\"actions\":[],\"behaviour\":{\"variables\":[],\"states\":[{\"name\":\"in_service\",\"initial\":true,\"transitions\":[{\"next\":\"stopped\",\"id\":\"message_stop_u_response_\",\"type\":\"response\",\"communication\":\"stop\"}]},{\"name\":\"stopped\",\"initial\":false,\"transitions\":[{\"next\":\"in_service\",\"id\":\"message_continue_u_response_\",\"type\":\"response\",\"communication\":\"continue\"}]}]}},{\"name\":\"TurtlebotPlatform\",\"messages\":[\"move\",\"halt\"],\"services\":[],\"actions\":[]}]}"; + output << "\"definition\": " << "{\"name\":\"LineFollowerController\",\"components\":[{\"name\":\"LineDetector\",\"messages\":[\"correction\",\"no_line\"],\"services\":[],\"actions\":[],\"behaviour\":{\"variables\":[\"current_correction\"],\"states\":[{\"name\":\"no_line\",\"initial\":true,\"transitions\":[{\"next\":\"line_found\",\"id\":\"message_correction_u_response_\",\"type\":\"response\",\"communication\":\"correction\"}]},{\"name\":\"line_found\",\"initial\":false,\"transitions\":[{\"next\":\"no_line\",\"id\":\"message_no_line_u_response_\",\"type\":\"response\",\"communication\":\"no_line\"},{\"next\":null,\"id\":\"message_correction_u_response_\",\"type\":\"response\",\"communication\":\"correction\"}]}]}},{\"name\":\"LidarSensor\",\"messages\":[\"scan\"],\"services\":[],\"actions\":[],\"behaviour\":{\"variables\":[\"current_distance\"],\"states\":[{\"name\":\"unsafe_distance\",\"initial\":true,\"transitions\":[{\"next\":\"safe_distance\",\"id\":\"component_LidarSensor_c_pVF9ZLWJF9HHG_\",\"type\":\"tau\"},{\"next\":null,\"id\":\"message_scan_u_response_\",\"type\":\"response\",\"communication\":\"scan\"}]},{\"name\":\"safe_distance\",\"initial\":false,\"transitions\":[{\"next\":\"unsafe_distance\",\"id\":\"component_LidarSensor_c_pIBXNH5R0L1DS_\",\"type\":\"tau\"},{\"next\":null,\"id\":\"message_scan_u_response_\",\"type\":\"response\",\"communication\":\"scan\"}]}]}},{\"name\":\"EmergencyStop\",\"messages\":[\"stop\",\"continue\"],\"services\":[],\"actions\":[],\"behaviour\":{\"variables\":[],\"states\":[{\"name\":\"in_service\",\"initial\":true,\"transitions\":[{\"next\":\"stopped\",\"id\":\"message_stop_u_response_\",\"type\":\"response\",\"communication\":\"stop\"}]},{\"name\":\"stopped\",\"initial\":false,\"transitions\":[{\"next\":\"in_service\",\"id\":\"message_continue_u_response_\",\"type\":\"response\",\"communication\":\"continue\"}]}]}},{\"name\":\"TurtlebotPlatform\",\"messages\":[\"move\",\"halt\"],\"services\":[],\"actions\":[]}]}"; output << "}"; auto msg = std_msgs::msg::String(); @@ -234,7 +234,7 @@ class Controller : public rclcpp::Node { // Heart of the controller void tick() { int nOfDataEvents = 2; - controller_Event_ data_events[2] = { data_move_c_p1FV6MKBBH2L7_,data_halt_c_pRJCB2BDWXUOW_ }; + controller_Event_ data_events[2] = { data_move_c_pLLL4DHRWZ0J5_,data_halt_c_p6PLB4ODMJIWE_ }; // Always execute data transitions that are possible shuffle_events(data_events, nOfDataEvents); @@ -244,12 +244,14 @@ class Controller : public rclcpp::Node { } int nOfControllableEvents = 4; - controller_Event_ controllable_events[4] = { component_LidarSensor_c_pL5GUHQARUVYQ_,component_LidarSensor_c_pOTNR1GAQDAZE_,message_move_c_trigger_,message_halt_c_trigger_ }; + controller_Event_ controllable_events[4] = { component_LidarSensor_c_pVF9ZLWJF9HHG_,component_LidarSensor_c_pIBXNH5R0L1DS_,message_move_c_trigger_,message_halt_c_trigger_ }; shuffle_events(controllable_events, nOfControllableEvents); for (int i = 0; i < nOfControllableEvents; i++) { - controller_EnginePerformEvent(controllable_events[i]); + if (controller_EnginePerformEvent(controllable_events[i])) { + break; + } } this->emit_current_state(); diff --git a/scenarios/scenario-1-line-follower/line_follower_controller.rscd b/scenarios/scenario-1-line-follower/line_follower_controller.rscd index 59a5ec2..5b64bec 100644 --- a/scenarios/scenario-1-line-follower/line_follower_controller.rscd +++ b/scenarios/scenario-1-line-follower/line_follower_controller.rscd @@ -8,7 +8,7 @@ robot LineFollowerController { behaviour { variable current_correction: double = 0.0 - initial state no_line { + initial marked state no_line { on response from correction goto line_found } @@ -36,7 +36,7 @@ robot LineFollowerController { on response from scan do current_distance := value - initial state unsafe_distance { + initial marked state unsafe_distance { transition if current_distance = safe goto safe_distance } @@ -58,4 +58,4 @@ robot LineFollowerController { } provide halt with { linear: { x: 0.0 }, angular: { z: 0.0 }} -} +} \ No newline at end of file diff --git a/scenarios/scenario-2-simple-navigation/controller/include/controller/controller_engine.c b/scenarios/scenario-2-simple-navigation/controller/include/controller/controller_engine.c index 004e7e9..42f1ee4 100644 --- a/scenarios/scenario-2-simple-navigation/controller/include/controller/controller_engine.c +++ b/scenarios/scenario-2-simple-navigation/controller/include/controller/controller_engine.c @@ -46,7 +46,7 @@ const char *controller_event_names[] = { "action_navigate.u_response", /**< Event action_navigate.u_response. */ "action_navigate.u_error", /**< Event action_navigate.u_error. */ "data_navigate.c_none", /**< Event data_navigate.c_none. */ - "data_navigate.c_p5DVFPXIKI0QU", /**< Event data_navigate.c_p5DVFPXIKI0QU. */ + "data_navigate.c_p1RWVCO75R33V", /**< Event data_navigate.c_p1RWVCO75R33V. */ "message_stop.u_response", /**< Event message_stop.u_response. */ "data_stop.c_none", /**< Event data_stop.c_none. */ "message_continue.u_response", /**< Event message_continue.u_response. */ @@ -56,7 +56,7 @@ const char *controller_event_names[] = { /** Enumeration names. */ const char *enum_names[] = { "awaiting_point", - "data_p1H8IM0967RAQ", + "data_pFXFXDZEMOW8W", "error", "executing", "has_point", @@ -298,26 +298,26 @@ static BoolType execEvent8(void) { } /** - * Execute code for event "data_navigate.c_p5DVFPXIKI0QU". + * Execute code for event "data_navigate.c_p1RWVCO75R33V". * * @return Whether the event was performed. */ static BoolType execEvent9(void) { - BoolType guard = ((data_navigate_) == (_controller_none)) || ((data_navigate_) == (_controller_data_p1H8IM0967RAQ)); + BoolType guard = ((data_navigate_) == (_controller_none)) || ((data_navigate_) == (_controller_data_pFXFXDZEMOW8W)); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_navigate_c_p5DVFPXIKI0QU_, TRUE); + controller_InfoEvent(data_navigate_c_p1RWVCO75R33V_, TRUE); #endif if ((data_navigate_) == (_controller_none)) { - data_navigate_ = _controller_data_p1H8IM0967RAQ; - } else if ((data_navigate_) == (_controller_data_p1H8IM0967RAQ)) { - data_navigate_ = _controller_data_p1H8IM0967RAQ; + data_navigate_ = _controller_data_pFXFXDZEMOW8W; + } else if ((data_navigate_) == (_controller_data_pFXFXDZEMOW8W)) { + data_navigate_ = _controller_data_pFXFXDZEMOW8W; } #if EVENT_OUTPUT - controller_InfoEvent(data_navigate_c_p5DVFPXIKI0QU_, FALSE); + controller_InfoEvent(data_navigate_c_p1RWVCO75R33V_, FALSE); #endif return TRUE; } @@ -502,7 +502,7 @@ static void PerformEvents(void) { if (execEvent6()) continue; /* (Try to) perform event "data_continue.c_none". */ if (execEvent7()) continue; /* (Try to) perform event "data_initial_pose.c_none". */ if (execEvent8()) continue; /* (Try to) perform event "data_navigate.c_none". */ - if (execEvent9()) continue; /* (Try to) perform event "data_navigate.c_p5DVFPXIKI0QU". */ + if (execEvent9()) continue; /* (Try to) perform event "data_navigate.c_p1RWVCO75R33V". */ if (execEvent10()) continue; /* (Try to) perform event "data_point.c_none". */ if (execEvent11()) continue; /* (Try to) perform event "data_stop.c_none". */ break; /* No event fired, done with discrete steps. */ @@ -585,7 +585,7 @@ BoolType controller_EnginePerformEvent(controller_Event_ event) { return execEvent7(); case data_navigate_c_none_: return execEvent8(); - case data_navigate_c_p5DVFPXIKI0QU_: + case data_navigate_c_p1RWVCO75R33V_: return execEvent9(); case data_point_c_none_: return execEvent10(); diff --git a/scenarios/scenario-2-simple-navigation/controller/include/controller/controller_engine.h b/scenarios/scenario-2-simple-navigation/controller/include/controller/controller_engine.h index 1f3272c..a0a37d7 100644 --- a/scenarios/scenario-2-simple-navigation/controller/include/controller/controller_engine.h +++ b/scenarios/scenario-2-simple-navigation/controller/include/controller/controller_engine.h @@ -12,7 +12,7 @@ */ enum Enumcontroller_ { _controller_awaiting_point, - _controller_data_p1H8IM0967RAQ, + _controller_data_pFXFXDZEMOW8W, _controller_error, _controller_executing, _controller_has_point, @@ -45,7 +45,7 @@ enum controllerEventEnum_ { action_navigate_u_response_, /**< Event action_navigate.u_response. */ action_navigate_u_error_, /**< Event action_navigate.u_error. */ data_navigate_c_none_, /**< Event data_navigate.c_none. */ - data_navigate_c_p5DVFPXIKI0QU_, /**< Event data_navigate.c_p5DVFPXIKI0QU. */ + data_navigate_c_p1RWVCO75R33V_, /**< Event data_navigate.c_p1RWVCO75R33V. */ message_stop_u_response_, /**< Event message_stop.u_response. */ data_stop_c_none_, /**< Event data_stop.c_none. */ message_continue_u_response_, /**< Event message_continue.u_response. */ diff --git a/scenarios/scenario-2-simple-navigation/controller/src/member_function.cpp b/scenarios/scenario-2-simple-navigation/controller/src/member_function.cpp index 81ca760..e973d28 100644 --- a/scenarios/scenario-2-simple-navigation/controller/src/member_function.cpp +++ b/scenarios/scenario-2-simple-navigation/controller/src/member_function.cpp @@ -149,7 +149,7 @@ class Controller : public rclcpp::Node { } auto goal_msg = nav2_msgs::action::NavigateToPose::Goal(); - if (data_navigate_ == _controller_data_p1H8IM0967RAQ) { + if (data_navigate_ == _controller_data_pFXFXDZEMOW8W) { goal_msg.pose.pose.position.x = code_Nav2_current_x; goal_msg.pose.pose.position.y = code_Nav2_current_y; goal_msg.pose.pose.position.z = code_Nav2_current_z; @@ -230,7 +230,7 @@ class Controller : public rclcpp::Node { // Heart of the controller void tick() { int nOfDataEvents = 1; - controller_Event_ data_events[1] = { data_navigate_c_p5DVFPXIKI0QU_ }; + controller_Event_ data_events[1] = { data_navigate_c_p1RWVCO75R33V_ }; // Always execute data transitions that are possible shuffle_events(data_events, nOfDataEvents); @@ -245,7 +245,9 @@ class Controller : public rclcpp::Node { shuffle_events(controllable_events, nOfControllableEvents); for (int i = 0; i < nOfControllableEvents; i++) { - controller_EnginePerformEvent(controllable_events[i]); + if (controller_EnginePerformEvent(controllable_events[i])) { + break; + } } this->emit_current_state(); diff --git a/scenarios/scenario-2-simple-navigation/simple_navigation.rscd b/scenarios/scenario-2-simple-navigation/simple_navigation.rscd index 038a2e8..f6d13c1 100644 --- a/scenarios/scenario-2-simple-navigation/simple_navigation.rscd +++ b/scenarios/scenario-2-simple-navigation/simple_navigation.rscd @@ -47,7 +47,7 @@ robot SimpleNavigation { on response from initial_pose goto awaiting_point } - state awaiting_point { + marked state awaiting_point { on response from point do current_x := value.point.x, current_y := value.point.y, current_z := value.point.z goto has_point } diff --git a/scenarios/scenario-3-obstacle-navigation/controller/include/controller/controller_engine.c b/scenarios/scenario-3-obstacle-navigation/controller/include/controller/controller_engine.c index 226ac83..2436bf9 100644 --- a/scenarios/scenario-3-obstacle-navigation/controller/include/controller/controller_engine.c +++ b/scenarios/scenario-3-obstacle-navigation/controller/include/controller/controller_engine.c @@ -46,7 +46,7 @@ const char *controller_event_names[] = { "action_navigate.u_response", /**< Event action_navigate.u_response. */ "action_navigate.u_error", /**< Event action_navigate.u_error. */ "data_navigate.c_none", /**< Event data_navigate.c_none. */ - "data_navigate.c_pFLTS95EOYOZG", /**< Event data_navigate.c_pFLTS95EOYOZG. */ + "data_navigate.c_p72TI1CQTP6QY", /**< Event data_navigate.c_p72TI1CQTP6QY. */ "message_stop.u_response", /**< Event message_stop.u_response. */ "data_stop.c_none", /**< Event data_stop.c_none. */ "message_continue.u_response", /**< Event message_continue.u_response. */ @@ -56,7 +56,7 @@ const char *controller_event_names[] = { /** Enumeration names. */ const char *enum_names[] = { "awaiting_point", - "data_p93Y3DT3CEL5Z", + "data_pO0APPT5EVPIR", "error", "executing", "has_point", @@ -298,26 +298,26 @@ static BoolType execEvent8(void) { } /** - * Execute code for event "data_navigate.c_pFLTS95EOYOZG". + * Execute code for event "data_navigate.c_p72TI1CQTP6QY". * * @return Whether the event was performed. */ static BoolType execEvent9(void) { - BoolType guard = ((data_navigate_) == (_controller_none)) || ((data_navigate_) == (_controller_data_p93Y3DT3CEL5Z)); + BoolType guard = ((data_navigate_) == (_controller_none)) || ((data_navigate_) == (_controller_data_pO0APPT5EVPIR)); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_navigate_c_pFLTS95EOYOZG_, TRUE); + controller_InfoEvent(data_navigate_c_p72TI1CQTP6QY_, TRUE); #endif if ((data_navigate_) == (_controller_none)) { - data_navigate_ = _controller_data_p93Y3DT3CEL5Z; - } else if ((data_navigate_) == (_controller_data_p93Y3DT3CEL5Z)) { - data_navigate_ = _controller_data_p93Y3DT3CEL5Z; + data_navigate_ = _controller_data_pO0APPT5EVPIR; + } else if ((data_navigate_) == (_controller_data_pO0APPT5EVPIR)) { + data_navigate_ = _controller_data_pO0APPT5EVPIR; } #if EVENT_OUTPUT - controller_InfoEvent(data_navigate_c_pFLTS95EOYOZG_, FALSE); + controller_InfoEvent(data_navigate_c_p72TI1CQTP6QY_, FALSE); #endif return TRUE; } @@ -502,7 +502,7 @@ static void PerformEvents(void) { if (execEvent6()) continue; /* (Try to) perform event "data_continue.c_none". */ if (execEvent7()) continue; /* (Try to) perform event "data_initial_pose.c_none". */ if (execEvent8()) continue; /* (Try to) perform event "data_navigate.c_none". */ - if (execEvent9()) continue; /* (Try to) perform event "data_navigate.c_pFLTS95EOYOZG". */ + if (execEvent9()) continue; /* (Try to) perform event "data_navigate.c_p72TI1CQTP6QY". */ if (execEvent10()) continue; /* (Try to) perform event "data_point.c_none". */ if (execEvent11()) continue; /* (Try to) perform event "data_stop.c_none". */ break; /* No event fired, done with discrete steps. */ @@ -585,7 +585,7 @@ BoolType controller_EnginePerformEvent(controller_Event_ event) { return execEvent7(); case data_navigate_c_none_: return execEvent8(); - case data_navigate_c_pFLTS95EOYOZG_: + case data_navigate_c_p72TI1CQTP6QY_: return execEvent9(); case data_point_c_none_: return execEvent10(); diff --git a/scenarios/scenario-3-obstacle-navigation/controller/include/controller/controller_engine.h b/scenarios/scenario-3-obstacle-navigation/controller/include/controller/controller_engine.h index 7f4fbb0..2a3d0a8 100644 --- a/scenarios/scenario-3-obstacle-navigation/controller/include/controller/controller_engine.h +++ b/scenarios/scenario-3-obstacle-navigation/controller/include/controller/controller_engine.h @@ -12,7 +12,7 @@ */ enum Enumcontroller_ { _controller_awaiting_point, - _controller_data_p93Y3DT3CEL5Z, + _controller_data_pO0APPT5EVPIR, _controller_error, _controller_executing, _controller_has_point, @@ -45,7 +45,7 @@ enum controllerEventEnum_ { action_navigate_u_response_, /**< Event action_navigate.u_response. */ action_navigate_u_error_, /**< Event action_navigate.u_error. */ data_navigate_c_none_, /**< Event data_navigate.c_none. */ - data_navigate_c_pFLTS95EOYOZG_, /**< Event data_navigate.c_pFLTS95EOYOZG. */ + data_navigate_c_p72TI1CQTP6QY_, /**< Event data_navigate.c_p72TI1CQTP6QY. */ message_stop_u_response_, /**< Event message_stop.u_response. */ data_stop_c_none_, /**< Event data_stop.c_none. */ message_continue_u_response_, /**< Event message_continue.u_response. */ diff --git a/scenarios/scenario-3-obstacle-navigation/controller/src/member_function.cpp b/scenarios/scenario-3-obstacle-navigation/controller/src/member_function.cpp index e0e38df..43e4c97 100644 --- a/scenarios/scenario-3-obstacle-navigation/controller/src/member_function.cpp +++ b/scenarios/scenario-3-obstacle-navigation/controller/src/member_function.cpp @@ -149,7 +149,7 @@ class Controller : public rclcpp::Node { } auto goal_msg = nav2_msgs::action::NavigateToPose::Goal(); - if (data_navigate_ == _controller_data_p93Y3DT3CEL5Z) { + if (data_navigate_ == _controller_data_pO0APPT5EVPIR) { goal_msg.pose.pose.position.x = code_Nav2_current_x; goal_msg.pose.pose.position.y = code_Nav2_current_y; goal_msg.pose.pose.position.z = code_Nav2_current_z; @@ -230,7 +230,7 @@ class Controller : public rclcpp::Node { // Heart of the controller void tick() { int nOfDataEvents = 1; - controller_Event_ data_events[1] = { data_navigate_c_pFLTS95EOYOZG_ }; + controller_Event_ data_events[1] = { data_navigate_c_p72TI1CQTP6QY_ }; // Always execute data transitions that are possible shuffle_events(data_events, nOfDataEvents); @@ -245,7 +245,9 @@ class Controller : public rclcpp::Node { shuffle_events(controllable_events, nOfControllableEvents); for (int i = 0; i < nOfControllableEvents; i++) { - controller_EnginePerformEvent(controllable_events[i]); + if (controller_EnginePerformEvent(controllable_events[i])) { + break; + } } this->emit_current_state(); diff --git a/scenarios/scenario-3-obstacle-navigation/obstacle_navigation.rscd b/scenarios/scenario-3-obstacle-navigation/obstacle_navigation.rscd index e4a9b5f..d3bda58 100644 --- a/scenarios/scenario-3-obstacle-navigation/obstacle_navigation.rscd +++ b/scenarios/scenario-3-obstacle-navigation/obstacle_navigation.rscd @@ -47,7 +47,7 @@ robot ObstacleNavigation { on response from initial_pose goto awaiting_point } - state awaiting_point { + marked state awaiting_point { on response from point do current_x := value.point.x, current_y := value.point.y, current_z := value.point.z goto has_point } diff --git a/scenarios/scenario-4-object-finder/object_finder.rscd b/scenarios/scenario-4-object-finder/object_finder.rscd index 1f4a916..bf70011 100644 --- a/scenarios/scenario-4-object-finder/object_finder.rscd +++ b/scenarios/scenario-4-object-finder/object_finder.rscd @@ -36,7 +36,7 @@ robot ObjectFinder { datatype enum ScannedObject from BoundingBoxes to { value.bounding_boxes[0].class_id = "stop sign" -> stop_sign - default -> no_object + default -> no_object_found } component LidarScanner { @@ -50,7 +50,7 @@ robot ObjectFinder { variable right: DistanceRight variable has_front: boolean = false - initial state sensing { + initial marked state sensing { on response from scan_front do front := value, has_front := true on response from scan_left do left := value on response from scan_right do right := value @@ -64,7 +64,7 @@ robot ObjectFinder { outgoing message rotate_done with identifier: "/rotate_done", type: none behaviour { - initial state awaiting_command { + initial marked state awaiting_command { on request to rotate_left goto executing on request to rotate_right goto executing } @@ -86,7 +86,7 @@ robot ObjectFinder { on response from object_count do scanned_object_count := value.count on response from object_scan do scanned_object := value - initial state no_object { + initial marked state no_object { transition if scanned_object_count > 0 and scanned_object = stop_sign goto object_found } diff --git a/scenarios/scenario-5-maze-solver/controller/include/controller/controller_engine.c b/scenarios/scenario-5-maze-solver/controller/include/controller/controller_engine.c index 05e0ef7..33c09c3 100644 --- a/scenarios/scenario-5-maze-solver/controller/include/controller/controller_engine.c +++ b/scenarios/scenario-5-maze-solver/controller/include/controller/controller_engine.c @@ -43,16 +43,16 @@ const char *controller_event_names[] = { "data_scan_diag_right.c_none", /**< Event data_scan_diag_right.c_none. */ "message_movement.c_trigger", /**< Event message_movement.c_trigger. */ "data_movement.c_none", /**< Event data_movement.c_none. */ - "data_movement.c_p6GUY3B2Y88AZ", /**< Event data_movement.c_p6GUY3B2Y88AZ. */ + "data_movement.c_pNVA8LDXZ1W47", /**< Event data_movement.c_pNVA8LDXZ1W47. */ "message_halt.c_trigger", /**< Event message_halt.c_trigger. */ "data_halt.c_none", /**< Event data_halt.c_none. */ - "data_halt.c_p5UHK7UNFZPYT", /**< Event data_halt.c_p5UHK7UNFZPYT. */ + "data_halt.c_p16BE8S338R6N", /**< Event data_halt.c_p16BE8S338R6N. */ "message_turn_left.c_trigger", /**< Event message_turn_left.c_trigger. */ "data_turn_left.c_none", /**< Event data_turn_left.c_none. */ - "data_turn_left.c_pUKB85UT3KGEA", /**< Event data_turn_left.c_pUKB85UT3KGEA. */ + "data_turn_left.c_pE8ZDXWKF7DDQ", /**< Event data_turn_left.c_pE8ZDXWKF7DDQ. */ "message_turn_right.c_trigger", /**< Event message_turn_right.c_trigger. */ "data_turn_right.c_none", /**< Event data_turn_right.c_none. */ - "data_turn_right.c_pSTZACE0OI243", /**< Event data_turn_right.c_pSTZACE0OI243. */ + "data_turn_right.c_pA9IRG3XACGBX", /**< Event data_turn_right.c_pA9IRG3XACGBX. */ "message_rotate_done.u_response", /**< Event message_rotate_done.u_response. */ "data_rotate_done.c_none", /**< Event data_rotate_done.c_none. */ "message_stop.u_response", /**< Event message_stop.u_response. */ @@ -63,10 +63,10 @@ const char *controller_event_names[] = { /** Enumeration names. */ const char *enum_names[] = { - "data_p4SNXF9MTRQWX", - "data_p6XQ99ZAH3DNB", - "data_pB4OUNV12MZEC", - "data_pV2HDUFCVMIEN", + "data_p0L2DOVIZA0HQ", + "data_p37TDJ4O4Z9W2", + "data_p56AAXCY6NDQE", + "data_p6Z88MTB24NZY", "in_service", "no_wall_diag_right", "no_wall_front", @@ -159,26 +159,26 @@ static BoolType execEvent1(void) { } /** - * Execute code for event "data_halt.c_p5UHK7UNFZPYT". + * Execute code for event "data_halt.c_p16BE8S338R6N". * * @return Whether the event was performed. */ static BoolType execEvent2(void) { - BoolType guard = ((data_halt_) == (_controller_none)) || ((data_halt_) == (_controller_data_p6XQ99ZAH3DNB)); + BoolType guard = ((data_halt_) == (_controller_none)) || ((data_halt_) == (_controller_data_p6Z88MTB24NZY)); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_halt_c_p5UHK7UNFZPYT_, TRUE); + controller_InfoEvent(data_halt_c_p16BE8S338R6N_, TRUE); #endif if ((data_halt_) == (_controller_none)) { - data_halt_ = _controller_data_p6XQ99ZAH3DNB; - } else if ((data_halt_) == (_controller_data_p6XQ99ZAH3DNB)) { - data_halt_ = _controller_data_p6XQ99ZAH3DNB; + data_halt_ = _controller_data_p6Z88MTB24NZY; + } else if ((data_halt_) == (_controller_data_p6Z88MTB24NZY)) { + data_halt_ = _controller_data_p6Z88MTB24NZY; } #if EVENT_OUTPUT - controller_InfoEvent(data_halt_c_p5UHK7UNFZPYT_, FALSE); + controller_InfoEvent(data_halt_c_p16BE8S338R6N_, FALSE); #endif return TRUE; } @@ -209,26 +209,26 @@ static BoolType execEvent3(void) { } /** - * Execute code for event "data_movement.c_p6GUY3B2Y88AZ". + * Execute code for event "data_movement.c_pNVA8LDXZ1W47". * * @return Whether the event was performed. */ static BoolType execEvent4(void) { - BoolType guard = ((data_movement_) == (_controller_none)) || ((data_movement_) == (_controller_data_pV2HDUFCVMIEN)); + BoolType guard = ((data_movement_) == (_controller_none)) || ((data_movement_) == (_controller_data_p56AAXCY6NDQE)); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_movement_c_p6GUY3B2Y88AZ_, TRUE); + controller_InfoEvent(data_movement_c_pNVA8LDXZ1W47_, TRUE); #endif if ((data_movement_) == (_controller_none)) { - data_movement_ = _controller_data_pV2HDUFCVMIEN; - } else if ((data_movement_) == (_controller_data_pV2HDUFCVMIEN)) { - data_movement_ = _controller_data_pV2HDUFCVMIEN; + data_movement_ = _controller_data_p56AAXCY6NDQE; + } else if ((data_movement_) == (_controller_data_p56AAXCY6NDQE)) { + data_movement_ = _controller_data_p56AAXCY6NDQE; } #if EVENT_OUTPUT - controller_InfoEvent(data_movement_c_p6GUY3B2Y88AZ_, FALSE); + controller_InfoEvent(data_movement_c_pNVA8LDXZ1W47_, FALSE); #endif return TRUE; } @@ -339,26 +339,26 @@ static BoolType execEvent10(void) { } /** - * Execute code for event "data_turn_left.c_pUKB85UT3KGEA". + * Execute code for event "data_turn_left.c_pE8ZDXWKF7DDQ". * * @return Whether the event was performed. */ static BoolType execEvent11(void) { - BoolType guard = ((data_turn_left_) == (_controller_none)) || ((data_turn_left_) == (_controller_data_p4SNXF9MTRQWX)); + BoolType guard = ((data_turn_left_) == (_controller_none)) || ((data_turn_left_) == (_controller_data_p37TDJ4O4Z9W2)); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_turn_left_c_pUKB85UT3KGEA_, TRUE); + controller_InfoEvent(data_turn_left_c_pE8ZDXWKF7DDQ_, TRUE); #endif if ((data_turn_left_) == (_controller_none)) { - data_turn_left_ = _controller_data_p4SNXF9MTRQWX; - } else if ((data_turn_left_) == (_controller_data_p4SNXF9MTRQWX)) { - data_turn_left_ = _controller_data_p4SNXF9MTRQWX; + data_turn_left_ = _controller_data_p37TDJ4O4Z9W2; + } else if ((data_turn_left_) == (_controller_data_p37TDJ4O4Z9W2)) { + data_turn_left_ = _controller_data_p37TDJ4O4Z9W2; } #if EVENT_OUTPUT - controller_InfoEvent(data_turn_left_c_pUKB85UT3KGEA_, FALSE); + controller_InfoEvent(data_turn_left_c_pE8ZDXWKF7DDQ_, FALSE); #endif return TRUE; } @@ -389,26 +389,26 @@ static BoolType execEvent12(void) { } /** - * Execute code for event "data_turn_right.c_pSTZACE0OI243". + * Execute code for event "data_turn_right.c_pA9IRG3XACGBX". * * @return Whether the event was performed. */ static BoolType execEvent13(void) { - BoolType guard = ((data_turn_right_) == (_controller_none)) || ((data_turn_right_) == (_controller_data_pB4OUNV12MZEC)); + BoolType guard = ((data_turn_right_) == (_controller_none)) || ((data_turn_right_) == (_controller_data_p0L2DOVIZA0HQ)); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_turn_right_c_pSTZACE0OI243_, TRUE); + controller_InfoEvent(data_turn_right_c_pA9IRG3XACGBX_, TRUE); #endif if ((data_turn_right_) == (_controller_none)) { - data_turn_right_ = _controller_data_pB4OUNV12MZEC; - } else if ((data_turn_right_) == (_controller_data_pB4OUNV12MZEC)) { - data_turn_right_ = _controller_data_pB4OUNV12MZEC; + data_turn_right_ = _controller_data_p0L2DOVIZA0HQ; + } else if ((data_turn_right_) == (_controller_data_p0L2DOVIZA0HQ)) { + data_turn_right_ = _controller_data_p0L2DOVIZA0HQ; } #if EVENT_OUTPUT - controller_InfoEvent(data_turn_right_c_pSTZACE0OI243_, FALSE); + controller_InfoEvent(data_turn_right_c_pA9IRG3XACGBX_, FALSE); #endif return TRUE; } @@ -676,18 +676,18 @@ static void PerformEvents(void) { if (execEvent0()) continue; /* (Try to) perform event "data_continue.c_none". */ if (execEvent1()) continue; /* (Try to) perform event "data_halt.c_none". */ - if (execEvent2()) continue; /* (Try to) perform event "data_halt.c_p5UHK7UNFZPYT". */ + if (execEvent2()) continue; /* (Try to) perform event "data_halt.c_p16BE8S338R6N". */ if (execEvent3()) continue; /* (Try to) perform event "data_movement.c_none". */ - if (execEvent4()) continue; /* (Try to) perform event "data_movement.c_p6GUY3B2Y88AZ". */ + if (execEvent4()) continue; /* (Try to) perform event "data_movement.c_pNVA8LDXZ1W47". */ if (execEvent5()) continue; /* (Try to) perform event "data_rotate_done.c_none". */ if (execEvent6()) continue; /* (Try to) perform event "data_scan_diag_right.c_none". */ if (execEvent7()) continue; /* (Try to) perform event "data_scan_front.c_none". */ if (execEvent8()) continue; /* (Try to) perform event "data_scan_right.c_none". */ if (execEvent9()) continue; /* (Try to) perform event "data_stop.c_none". */ if (execEvent10()) continue; /* (Try to) perform event "data_turn_left.c_none". */ - if (execEvent11()) continue; /* (Try to) perform event "data_turn_left.c_pUKB85UT3KGEA". */ + if (execEvent11()) continue; /* (Try to) perform event "data_turn_left.c_pE8ZDXWKF7DDQ". */ if (execEvent12()) continue; /* (Try to) perform event "data_turn_right.c_none". */ - if (execEvent13()) continue; /* (Try to) perform event "data_turn_right.c_pSTZACE0OI243". */ + if (execEvent13()) continue; /* (Try to) perform event "data_turn_right.c_pA9IRG3XACGBX". */ if (execEvent15()) continue; /* (Try to) perform event "message_halt.c_trigger". */ if (execEvent16()) continue; /* (Try to) perform event "message_movement.c_trigger". */ if (execEvent22()) continue; /* (Try to) perform event "message_turn_left.c_trigger". */ @@ -763,11 +763,11 @@ BoolType controller_EnginePerformEvent(controller_Event_ event) { return execEvent0(); case data_halt_c_none_: return execEvent1(); - case data_halt_c_p5UHK7UNFZPYT_: + case data_halt_c_p16BE8S338R6N_: return execEvent2(); case data_movement_c_none_: return execEvent3(); - case data_movement_c_p6GUY3B2Y88AZ_: + case data_movement_c_pNVA8LDXZ1W47_: return execEvent4(); case data_rotate_done_c_none_: return execEvent5(); @@ -781,11 +781,11 @@ BoolType controller_EnginePerformEvent(controller_Event_ event) { return execEvent9(); case data_turn_left_c_none_: return execEvent10(); - case data_turn_left_c_pUKB85UT3KGEA_: + case data_turn_left_c_pE8ZDXWKF7DDQ_: return execEvent11(); case data_turn_right_c_none_: return execEvent12(); - case data_turn_right_c_pSTZACE0OI243_: + case data_turn_right_c_pA9IRG3XACGBX_: return execEvent13(); case message_continue_u_response_: return execEvent14(); diff --git a/scenarios/scenario-5-maze-solver/controller/include/controller/controller_engine.h b/scenarios/scenario-5-maze-solver/controller/include/controller/controller_engine.h index d34418d..39fcd13 100644 --- a/scenarios/scenario-5-maze-solver/controller/include/controller/controller_engine.h +++ b/scenarios/scenario-5-maze-solver/controller/include/controller/controller_engine.h @@ -11,10 +11,10 @@ * Note that integer ranges are ignored in C. */ enum Enumcontroller_ { - _controller_data_p4SNXF9MTRQWX, - _controller_data_p6XQ99ZAH3DNB, - _controller_data_pB4OUNV12MZEC, - _controller_data_pV2HDUFCVMIEN, + _controller_data_p0L2DOVIZA0HQ, + _controller_data_p37TDJ4O4Z9W2, + _controller_data_p56AAXCY6NDQE, + _controller_data_p6Z88MTB24NZY, _controller_in_service, _controller_no_wall_diag_right, _controller_no_wall_front, @@ -46,16 +46,16 @@ enum controllerEventEnum_ { data_scan_diag_right_c_none_, /**< Event data_scan_diag_right.c_none. */ message_movement_c_trigger_, /**< Event message_movement.c_trigger. */ data_movement_c_none_, /**< Event data_movement.c_none. */ - data_movement_c_p6GUY3B2Y88AZ_, /**< Event data_movement.c_p6GUY3B2Y88AZ. */ + data_movement_c_pNVA8LDXZ1W47_, /**< Event data_movement.c_pNVA8LDXZ1W47. */ message_halt_c_trigger_, /**< Event message_halt.c_trigger. */ data_halt_c_none_, /**< Event data_halt.c_none. */ - data_halt_c_p5UHK7UNFZPYT_, /**< Event data_halt.c_p5UHK7UNFZPYT. */ + data_halt_c_p16BE8S338R6N_, /**< Event data_halt.c_p16BE8S338R6N. */ message_turn_left_c_trigger_, /**< Event message_turn_left.c_trigger. */ data_turn_left_c_none_, /**< Event data_turn_left.c_none. */ - data_turn_left_c_pUKB85UT3KGEA_, /**< Event data_turn_left.c_pUKB85UT3KGEA. */ + data_turn_left_c_pE8ZDXWKF7DDQ_, /**< Event data_turn_left.c_pE8ZDXWKF7DDQ. */ message_turn_right_c_trigger_, /**< Event message_turn_right.c_trigger. */ data_turn_right_c_none_, /**< Event data_turn_right.c_none. */ - data_turn_right_c_pSTZACE0OI243_, /**< Event data_turn_right.c_pSTZACE0OI243. */ + data_turn_right_c_pA9IRG3XACGBX_, /**< Event data_turn_right.c_pA9IRG3XACGBX. */ message_rotate_done_u_response_, /**< Event message_rotate_done.u_response. */ data_rotate_done_c_none_, /**< Event data_rotate_done.c_none. */ message_stop_u_response_, /**< Event message_stop.u_response. */ diff --git a/scenarios/scenario-5-maze-solver/controller/src/member_function.cpp b/scenarios/scenario-5-maze-solver/controller/src/member_function.cpp index 26c1f14..cefa390 100644 --- a/scenarios/scenario-5-maze-solver/controller/src/member_function.cpp +++ b/scenarios/scenario-5-maze-solver/controller/src/member_function.cpp @@ -169,7 +169,7 @@ class Controller : public rclcpp::Node { void call_message_movement() { auto value = geometry_msgs::msg::Twist(); - if (data_movement_ == _controller_data_pV2HDUFCVMIEN) { + if (data_movement_ == _controller_data_p56AAXCY6NDQE) { value.linear.x = 0.3; } @@ -181,7 +181,7 @@ class Controller : public rclcpp::Node { void call_message_halt() { auto value = geometry_msgs::msg::Twist(); - if (data_halt_ == _controller_data_p6XQ99ZAH3DNB) { + if (data_halt_ == _controller_data_p6Z88MTB24NZY) { value.linear.x = 0.0; } @@ -193,7 +193,7 @@ class Controller : public rclcpp::Node { void call_message_turn_left() { auto value = std_msgs::msg::Int16(); - if (data_turn_left_ == _controller_data_p4SNXF9MTRQWX) { + if (data_turn_left_ == _controller_data_p37TDJ4O4Z9W2) { value.data = 90; } @@ -205,7 +205,7 @@ class Controller : public rclcpp::Node { void call_message_turn_right() { auto value = std_msgs::msg::Int16(); - if (data_turn_right_ == _controller_data_pB4OUNV12MZEC) { + if (data_turn_right_ == _controller_data_p0L2DOVIZA0HQ) { value.data = 90; } @@ -293,7 +293,7 @@ class Controller : public rclcpp::Node { // Heart of the controller void tick() { int nOfDataEvents = 4; - controller_Event_ data_events[4] = { data_movement_c_p6GUY3B2Y88AZ_,data_halt_c_p5UHK7UNFZPYT_,data_turn_left_c_pUKB85UT3KGEA_,data_turn_right_c_pSTZACE0OI243_ }; + controller_Event_ data_events[4] = { data_movement_c_pNVA8LDXZ1W47_,data_halt_c_p16BE8S338R6N_,data_turn_left_c_pE8ZDXWKF7DDQ_,data_turn_right_c_pA9IRG3XACGBX_ }; // Always execute data transitions that are possible shuffle_events(data_events, nOfDataEvents); @@ -308,7 +308,9 @@ class Controller : public rclcpp::Node { shuffle_events(controllable_events, nOfControllableEvents); for (int i = 0; i < nOfControllableEvents; i++) { - controller_EnginePerformEvent(controllable_events[i]); + if (controller_EnginePerformEvent(controllable_events[i])) { + break; + } } this->emit_current_state(); diff --git a/scenarios/scenario-5-maze-solver/maze_solver.rscd b/scenarios/scenario-5-maze-solver/maze_solver.rscd index 34ca98b..8744bb3 100644 --- a/scenarios/scenario-5-maze-solver/maze_solver.rscd +++ b/scenarios/scenario-5-maze-solver/maze_solver.rscd @@ -46,7 +46,7 @@ robot MazeSolver { on response from scan_front do front := value on response from scan_diag_right do diag_right := value - initial state sensing {} + initial marked state sensing {} } } @@ -60,7 +60,7 @@ robot MazeSolver { outgoing message rotate_done with identifier: "/rotate_done", type: none behaviour { - initial state ready { + initial marked state ready { on request to turn_left goto turning on request to turn_right goto turning } diff --git a/scenarios/scenario-6-push-ball-goal/controller/include/controller/controller_engine.c b/scenarios/scenario-6-push-ball-goal/controller/include/controller/controller_engine.c index b15b40a..ad2f5a4 100644 --- a/scenarios/scenario-6-push-ball-goal/controller/include/controller/controller_engine.c +++ b/scenarios/scenario-6-push-ball-goal/controller/include/controller/controller_engine.c @@ -57,13 +57,13 @@ const char *controller_event_names[] = { "data_continue.c_none", /**< Event data_continue.c_none. */ "message_move.c_trigger", /**< Event message_move.c_trigger. */ "data_move.c_none", /**< Event data_move.c_none. */ - "data_move.c_pNLRTW551QX6M", /**< Event data_move.c_pNLRTW551QX6M. */ - "data_move.c_pLQBN5IDMMNA0", /**< Event data_move.c_pLQBN5IDMMNA0. */ - "data_move.c_pZ6VVX7FHA9UC", /**< Event data_move.c_pZ6VVX7FHA9UC. */ - "data_move.c_pHKVHWHN6EUM1", /**< Event data_move.c_pHKVHWHN6EUM1. */ + "data_move.c_p0MTC7HSVMD25", /**< Event data_move.c_p0MTC7HSVMD25. */ + "data_move.c_pPLIRMHMV31U1", /**< Event data_move.c_pPLIRMHMV31U1. */ + "data_move.c_pWKYXT98G57H5", /**< Event data_move.c_pWKYXT98G57H5. */ + "data_move.c_pYG2W44S9M0LS", /**< Event data_move.c_pYG2W44S9M0LS. */ "message_halt.c_trigger", /**< Event message_halt.c_trigger. */ "data_halt.c_none", /**< Event data_halt.c_none. */ - "data_halt.c_p7A4YL2QMRJC0", /**< Event data_halt.c_p7A4YL2QMRJC0. */ + "data_halt.c_p9DORKK07C1FW", /**< Event data_halt.c_p9DORKK07C1FW. */ }; /** Enumeration names. */ @@ -72,11 +72,11 @@ const char *enum_names[] = { "awaiting", "ball_found", "ball_in_front", - "data_p3FWU5LJD83KP", - "data_pT6I8XRJ5MOT3", - "data_pWKTMPZDWUE17", - "data_pZQUQLRDM9OJ6", - "data_pZQUXVJGJO0YV", + "data_p19ECF3KTP0U8", + "data_pCAZ89YPHWXZQ", + "data_pEPMG0RA510TK", + "data_pG91L42WDTXHW", + "data_pHT24JRO2029H", "free", "goal_found", "in_service", @@ -209,26 +209,26 @@ static BoolType execEvent4(void) { } /** - * Execute code for event "data_halt.c_p7A4YL2QMRJC0". + * Execute code for event "data_halt.c_p9DORKK07C1FW". * * @return Whether the event was performed. */ static BoolType execEvent5(void) { - BoolType guard = ((data_halt_) == (_controller_none)) || ((data_halt_) == (_controller_data_pT6I8XRJ5MOT3)); + BoolType guard = ((data_halt_) == (_controller_none)) || ((data_halt_) == (_controller_data_p19ECF3KTP0U8)); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_halt_c_p7A4YL2QMRJC0_, TRUE); + controller_InfoEvent(data_halt_c_p9DORKK07C1FW_, TRUE); #endif if ((data_halt_) == (_controller_none)) { - data_halt_ = _controller_data_pT6I8XRJ5MOT3; - } else if ((data_halt_) == (_controller_data_pT6I8XRJ5MOT3)) { - data_halt_ = _controller_data_pT6I8XRJ5MOT3; + data_halt_ = _controller_data_p19ECF3KTP0U8; + } else if ((data_halt_) == (_controller_data_p19ECF3KTP0U8)) { + data_halt_ = _controller_data_p19ECF3KTP0U8; } #if EVENT_OUTPUT - controller_InfoEvent(data_halt_c_p7A4YL2QMRJC0_, FALSE); + controller_InfoEvent(data_halt_c_p9DORKK07C1FW_, FALSE); #endif return TRUE; } @@ -239,7 +239,7 @@ static BoolType execEvent5(void) { * @return Whether the event was performed. */ static BoolType execEvent6(void) { - BoolType guard = (((((data_move_) == (_controller_none)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) || ((((data_move_) == (_controller_data_p3FWU5LJD83KP)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball)))))) || (((((data_move_) == (_controller_data_pZQUQLRDM9OJ6)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) || (((((data_move_) == (_controller_data_pZQUXVJGJO0YV)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) || ((((data_move_) == (_controller_data_pWKTMPZDWUE17)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))))); + BoolType guard = (((((data_move_) == (_controller_none)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) || ((((data_move_) == (_controller_data_pG91L42WDTXHW)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball)))))) || (((((data_move_) == (_controller_data_pEPMG0RA510TK)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) || (((((data_move_) == (_controller_data_pCAZ89YPHWXZQ)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) || ((((data_move_) == (_controller_data_pHT24JRO2029H)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))))); if (!guard) return FALSE; #if EVENT_OUTPUT @@ -248,13 +248,13 @@ static BoolType execEvent6(void) { if ((((data_move_) == (_controller_none)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) { data_move_ = _controller_none; - } else if ((((data_move_) == (_controller_data_p3FWU5LJD83KP)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) { + } else if ((((data_move_) == (_controller_data_pG91L42WDTXHW)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) { data_move_ = _controller_none; - } else if ((((data_move_) == (_controller_data_pZQUQLRDM9OJ6)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) { + } else if ((((data_move_) == (_controller_data_pEPMG0RA510TK)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) { data_move_ = _controller_none; - } else if ((((data_move_) == (_controller_data_pZQUXVJGJO0YV)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) { + } else if ((((data_move_) == (_controller_data_pCAZ89YPHWXZQ)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) { data_move_ = _controller_none; - } else if ((((data_move_) == (_controller_data_pWKTMPZDWUE17)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) { + } else if ((((data_move_) == (_controller_data_pHT24JRO2029H)) && ((component_BallDetector_ != _controller_ball_found))) && (((component_BallDetector_ != _controller_adjusting)) && (((component_BallDetector_ != _controller_ball_in_front)) && ((component_BallDetector_ != _controller_no_ball))))) { data_move_ = _controller_none; } @@ -265,125 +265,125 @@ static BoolType execEvent6(void) { } /** - * Execute code for event "data_move.c_pHKVHWHN6EUM1". + * Execute code for event "data_move.c_p0MTC7HSVMD25". * * @return Whether the event was performed. */ static BoolType execEvent7(void) { - BoolType guard = ((((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_no_ball))) || (((data_move_) == (_controller_data_p3FWU5LJD83KP)) && ((component_BallDetector_) == (_controller_no_ball)))) || ((((data_move_) == (_controller_data_pZQUQLRDM9OJ6)) && ((component_BallDetector_) == (_controller_no_ball))) || ((((data_move_) == (_controller_data_pZQUXVJGJO0YV)) && ((component_BallDetector_) == (_controller_no_ball))) || (((data_move_) == (_controller_data_pWKTMPZDWUE17)) && ((component_BallDetector_) == (_controller_no_ball))))); + BoolType guard = ((((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_ball_found))) || (((data_move_) == (_controller_data_pG91L42WDTXHW)) && ((component_BallDetector_) == (_controller_ball_found)))) || ((((data_move_) == (_controller_data_pEPMG0RA510TK)) && ((component_BallDetector_) == (_controller_ball_found))) || ((((data_move_) == (_controller_data_pCAZ89YPHWXZQ)) && ((component_BallDetector_) == (_controller_ball_found))) || (((data_move_) == (_controller_data_pHT24JRO2029H)) && ((component_BallDetector_) == (_controller_ball_found))))); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_pHKVHWHN6EUM1_, TRUE); + controller_InfoEvent(data_move_c_p0MTC7HSVMD25_, TRUE); #endif - if (((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_no_ball))) { - data_move_ = _controller_data_pWKTMPZDWUE17; - } else if (((data_move_) == (_controller_data_p3FWU5LJD83KP)) && ((component_BallDetector_) == (_controller_no_ball))) { - data_move_ = _controller_data_pWKTMPZDWUE17; - } else if (((data_move_) == (_controller_data_pZQUQLRDM9OJ6)) && ((component_BallDetector_) == (_controller_no_ball))) { - data_move_ = _controller_data_pWKTMPZDWUE17; - } else if (((data_move_) == (_controller_data_pZQUXVJGJO0YV)) && ((component_BallDetector_) == (_controller_no_ball))) { - data_move_ = _controller_data_pWKTMPZDWUE17; - } else if (((data_move_) == (_controller_data_pWKTMPZDWUE17)) && ((component_BallDetector_) == (_controller_no_ball))) { - data_move_ = _controller_data_pWKTMPZDWUE17; + if (((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_ball_found))) { + data_move_ = _controller_data_pG91L42WDTXHW; + } else if (((data_move_) == (_controller_data_pG91L42WDTXHW)) && ((component_BallDetector_) == (_controller_ball_found))) { + data_move_ = _controller_data_pG91L42WDTXHW; + } else if (((data_move_) == (_controller_data_pEPMG0RA510TK)) && ((component_BallDetector_) == (_controller_ball_found))) { + data_move_ = _controller_data_pG91L42WDTXHW; + } else if (((data_move_) == (_controller_data_pCAZ89YPHWXZQ)) && ((component_BallDetector_) == (_controller_ball_found))) { + data_move_ = _controller_data_pG91L42WDTXHW; + } else if (((data_move_) == (_controller_data_pHT24JRO2029H)) && ((component_BallDetector_) == (_controller_ball_found))) { + data_move_ = _controller_data_pG91L42WDTXHW; } #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_pHKVHWHN6EUM1_, FALSE); + controller_InfoEvent(data_move_c_p0MTC7HSVMD25_, FALSE); #endif return TRUE; } /** - * Execute code for event "data_move.c_pLQBN5IDMMNA0". + * Execute code for event "data_move.c_pPLIRMHMV31U1". * * @return Whether the event was performed. */ static BoolType execEvent8(void) { - BoolType guard = ((((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_adjusting))) || (((data_move_) == (_controller_data_p3FWU5LJD83KP)) && ((component_BallDetector_) == (_controller_adjusting)))) || ((((data_move_) == (_controller_data_pZQUQLRDM9OJ6)) && ((component_BallDetector_) == (_controller_adjusting))) || ((((data_move_) == (_controller_data_pZQUXVJGJO0YV)) && ((component_BallDetector_) == (_controller_adjusting))) || (((data_move_) == (_controller_data_pWKTMPZDWUE17)) && ((component_BallDetector_) == (_controller_adjusting))))); + BoolType guard = ((((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_adjusting))) || (((data_move_) == (_controller_data_pG91L42WDTXHW)) && ((component_BallDetector_) == (_controller_adjusting)))) || ((((data_move_) == (_controller_data_pEPMG0RA510TK)) && ((component_BallDetector_) == (_controller_adjusting))) || ((((data_move_) == (_controller_data_pCAZ89YPHWXZQ)) && ((component_BallDetector_) == (_controller_adjusting))) || (((data_move_) == (_controller_data_pHT24JRO2029H)) && ((component_BallDetector_) == (_controller_adjusting))))); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_pLQBN5IDMMNA0_, TRUE); + controller_InfoEvent(data_move_c_pPLIRMHMV31U1_, TRUE); #endif if (((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_adjusting))) { - data_move_ = _controller_data_pZQUQLRDM9OJ6; - } else if (((data_move_) == (_controller_data_p3FWU5LJD83KP)) && ((component_BallDetector_) == (_controller_adjusting))) { - data_move_ = _controller_data_pZQUQLRDM9OJ6; - } else if (((data_move_) == (_controller_data_pZQUQLRDM9OJ6)) && ((component_BallDetector_) == (_controller_adjusting))) { - data_move_ = _controller_data_pZQUQLRDM9OJ6; - } else if (((data_move_) == (_controller_data_pZQUXVJGJO0YV)) && ((component_BallDetector_) == (_controller_adjusting))) { - data_move_ = _controller_data_pZQUQLRDM9OJ6; - } else if (((data_move_) == (_controller_data_pWKTMPZDWUE17)) && ((component_BallDetector_) == (_controller_adjusting))) { - data_move_ = _controller_data_pZQUQLRDM9OJ6; + data_move_ = _controller_data_pEPMG0RA510TK; + } else if (((data_move_) == (_controller_data_pG91L42WDTXHW)) && ((component_BallDetector_) == (_controller_adjusting))) { + data_move_ = _controller_data_pEPMG0RA510TK; + } else if (((data_move_) == (_controller_data_pEPMG0RA510TK)) && ((component_BallDetector_) == (_controller_adjusting))) { + data_move_ = _controller_data_pEPMG0RA510TK; + } else if (((data_move_) == (_controller_data_pCAZ89YPHWXZQ)) && ((component_BallDetector_) == (_controller_adjusting))) { + data_move_ = _controller_data_pEPMG0RA510TK; + } else if (((data_move_) == (_controller_data_pHT24JRO2029H)) && ((component_BallDetector_) == (_controller_adjusting))) { + data_move_ = _controller_data_pEPMG0RA510TK; } #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_pLQBN5IDMMNA0_, FALSE); + controller_InfoEvent(data_move_c_pPLIRMHMV31U1_, FALSE); #endif return TRUE; } /** - * Execute code for event "data_move.c_pNLRTW551QX6M". + * Execute code for event "data_move.c_pWKYXT98G57H5". * * @return Whether the event was performed. */ static BoolType execEvent9(void) { - BoolType guard = ((((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_ball_found))) || (((data_move_) == (_controller_data_p3FWU5LJD83KP)) && ((component_BallDetector_) == (_controller_ball_found)))) || ((((data_move_) == (_controller_data_pZQUQLRDM9OJ6)) && ((component_BallDetector_) == (_controller_ball_found))) || ((((data_move_) == (_controller_data_pZQUXVJGJO0YV)) && ((component_BallDetector_) == (_controller_ball_found))) || (((data_move_) == (_controller_data_pWKTMPZDWUE17)) && ((component_BallDetector_) == (_controller_ball_found))))); + BoolType guard = ((((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_ball_in_front))) || (((data_move_) == (_controller_data_pG91L42WDTXHW)) && ((component_BallDetector_) == (_controller_ball_in_front)))) || ((((data_move_) == (_controller_data_pEPMG0RA510TK)) && ((component_BallDetector_) == (_controller_ball_in_front))) || ((((data_move_) == (_controller_data_pCAZ89YPHWXZQ)) && ((component_BallDetector_) == (_controller_ball_in_front))) || (((data_move_) == (_controller_data_pHT24JRO2029H)) && ((component_BallDetector_) == (_controller_ball_in_front))))); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_pNLRTW551QX6M_, TRUE); + controller_InfoEvent(data_move_c_pWKYXT98G57H5_, TRUE); #endif - if (((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_ball_found))) { - data_move_ = _controller_data_p3FWU5LJD83KP; - } else if (((data_move_) == (_controller_data_p3FWU5LJD83KP)) && ((component_BallDetector_) == (_controller_ball_found))) { - data_move_ = _controller_data_p3FWU5LJD83KP; - } else if (((data_move_) == (_controller_data_pZQUQLRDM9OJ6)) && ((component_BallDetector_) == (_controller_ball_found))) { - data_move_ = _controller_data_p3FWU5LJD83KP; - } else if (((data_move_) == (_controller_data_pZQUXVJGJO0YV)) && ((component_BallDetector_) == (_controller_ball_found))) { - data_move_ = _controller_data_p3FWU5LJD83KP; - } else if (((data_move_) == (_controller_data_pWKTMPZDWUE17)) && ((component_BallDetector_) == (_controller_ball_found))) { - data_move_ = _controller_data_p3FWU5LJD83KP; + if (((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_ball_in_front))) { + data_move_ = _controller_data_pCAZ89YPHWXZQ; + } else if (((data_move_) == (_controller_data_pG91L42WDTXHW)) && ((component_BallDetector_) == (_controller_ball_in_front))) { + data_move_ = _controller_data_pCAZ89YPHWXZQ; + } else if (((data_move_) == (_controller_data_pEPMG0RA510TK)) && ((component_BallDetector_) == (_controller_ball_in_front))) { + data_move_ = _controller_data_pCAZ89YPHWXZQ; + } else if (((data_move_) == (_controller_data_pCAZ89YPHWXZQ)) && ((component_BallDetector_) == (_controller_ball_in_front))) { + data_move_ = _controller_data_pCAZ89YPHWXZQ; + } else if (((data_move_) == (_controller_data_pHT24JRO2029H)) && ((component_BallDetector_) == (_controller_ball_in_front))) { + data_move_ = _controller_data_pCAZ89YPHWXZQ; } #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_pNLRTW551QX6M_, FALSE); + controller_InfoEvent(data_move_c_pWKYXT98G57H5_, FALSE); #endif return TRUE; } /** - * Execute code for event "data_move.c_pZ6VVX7FHA9UC". + * Execute code for event "data_move.c_pYG2W44S9M0LS". * * @return Whether the event was performed. */ static BoolType execEvent10(void) { - BoolType guard = ((((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_ball_in_front))) || (((data_move_) == (_controller_data_p3FWU5LJD83KP)) && ((component_BallDetector_) == (_controller_ball_in_front)))) || ((((data_move_) == (_controller_data_pZQUQLRDM9OJ6)) && ((component_BallDetector_) == (_controller_ball_in_front))) || ((((data_move_) == (_controller_data_pZQUXVJGJO0YV)) && ((component_BallDetector_) == (_controller_ball_in_front))) || (((data_move_) == (_controller_data_pWKTMPZDWUE17)) && ((component_BallDetector_) == (_controller_ball_in_front))))); + BoolType guard = ((((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_no_ball))) || (((data_move_) == (_controller_data_pG91L42WDTXHW)) && ((component_BallDetector_) == (_controller_no_ball)))) || ((((data_move_) == (_controller_data_pEPMG0RA510TK)) && ((component_BallDetector_) == (_controller_no_ball))) || ((((data_move_) == (_controller_data_pCAZ89YPHWXZQ)) && ((component_BallDetector_) == (_controller_no_ball))) || (((data_move_) == (_controller_data_pHT24JRO2029H)) && ((component_BallDetector_) == (_controller_no_ball))))); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_pZ6VVX7FHA9UC_, TRUE); + controller_InfoEvent(data_move_c_pYG2W44S9M0LS_, TRUE); #endif - if (((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_ball_in_front))) { - data_move_ = _controller_data_pZQUXVJGJO0YV; - } else if (((data_move_) == (_controller_data_p3FWU5LJD83KP)) && ((component_BallDetector_) == (_controller_ball_in_front))) { - data_move_ = _controller_data_pZQUXVJGJO0YV; - } else if (((data_move_) == (_controller_data_pZQUQLRDM9OJ6)) && ((component_BallDetector_) == (_controller_ball_in_front))) { - data_move_ = _controller_data_pZQUXVJGJO0YV; - } else if (((data_move_) == (_controller_data_pZQUXVJGJO0YV)) && ((component_BallDetector_) == (_controller_ball_in_front))) { - data_move_ = _controller_data_pZQUXVJGJO0YV; - } else if (((data_move_) == (_controller_data_pWKTMPZDWUE17)) && ((component_BallDetector_) == (_controller_ball_in_front))) { - data_move_ = _controller_data_pZQUXVJGJO0YV; + if (((data_move_) == (_controller_none)) && ((component_BallDetector_) == (_controller_no_ball))) { + data_move_ = _controller_data_pHT24JRO2029H; + } else if (((data_move_) == (_controller_data_pG91L42WDTXHW)) && ((component_BallDetector_) == (_controller_no_ball))) { + data_move_ = _controller_data_pHT24JRO2029H; + } else if (((data_move_) == (_controller_data_pEPMG0RA510TK)) && ((component_BallDetector_) == (_controller_no_ball))) { + data_move_ = _controller_data_pHT24JRO2029H; + } else if (((data_move_) == (_controller_data_pCAZ89YPHWXZQ)) && ((component_BallDetector_) == (_controller_no_ball))) { + data_move_ = _controller_data_pHT24JRO2029H; + } else if (((data_move_) == (_controller_data_pHT24JRO2029H)) && ((component_BallDetector_) == (_controller_no_ball))) { + data_move_ = _controller_data_pHT24JRO2029H; } #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_pZ6VVX7FHA9UC_, FALSE); + controller_InfoEvent(data_move_c_pYG2W44S9M0LS_, FALSE); #endif return TRUE; } @@ -845,12 +845,12 @@ static void PerformEvents(void) { if (execEvent2()) continue; /* (Try to) perform event "data_continue.c_none". */ if (execEvent3()) continue; /* (Try to) perform event "data_goal_correction.c_none". */ if (execEvent4()) continue; /* (Try to) perform event "data_halt.c_none". */ - if (execEvent5()) continue; /* (Try to) perform event "data_halt.c_p7A4YL2QMRJC0". */ + if (execEvent5()) continue; /* (Try to) perform event "data_halt.c_p9DORKK07C1FW". */ if (execEvent6()) continue; /* (Try to) perform event "data_move.c_none". */ - if (execEvent7()) continue; /* (Try to) perform event "data_move.c_pHKVHWHN6EUM1". */ - if (execEvent8()) continue; /* (Try to) perform event "data_move.c_pLQBN5IDMMNA0". */ - if (execEvent9()) continue; /* (Try to) perform event "data_move.c_pNLRTW551QX6M". */ - if (execEvent10()) continue; /* (Try to) perform event "data_move.c_pZ6VVX7FHA9UC". */ + if (execEvent7()) continue; /* (Try to) perform event "data_move.c_p0MTC7HSVMD25". */ + if (execEvent8()) continue; /* (Try to) perform event "data_move.c_pPLIRMHMV31U1". */ + if (execEvent9()) continue; /* (Try to) perform event "data_move.c_pWKYXT98G57H5". */ + if (execEvent10()) continue; /* (Try to) perform event "data_move.c_pYG2W44S9M0LS". */ if (execEvent11()) continue; /* (Try to) perform event "data_needs_ajustment.c_none". */ if (execEvent12()) continue; /* (Try to) perform event "data_no_adjustment.c_none". */ if (execEvent13()) continue; /* (Try to) perform event "data_no_ball.c_none". */ @@ -872,7 +872,7 @@ void controller_EngineFirstStep(void) { component_BallDetector_ = _controller_awaiting; component_EmergencyStop_ = _controller_in_service; component_GoalDetector_ = _controller_awaiting; - component_Scanner_v_distance_ = _controller_obstructed; + component_Scanner_v_distance_ = _controller_free; data_halt_ = _controller_none; data_move_ = _controller_none; @@ -933,17 +933,17 @@ BoolType controller_EnginePerformEvent(controller_Event_ event) { return execEvent3(); case data_halt_c_none_: return execEvent4(); - case data_halt_c_p7A4YL2QMRJC0_: + case data_halt_c_p9DORKK07C1FW_: return execEvent5(); case data_move_c_none_: return execEvent6(); - case data_move_c_pHKVHWHN6EUM1_: + case data_move_c_p0MTC7HSVMD25_: return execEvent7(); - case data_move_c_pLQBN5IDMMNA0_: + case data_move_c_pPLIRMHMV31U1_: return execEvent8(); - case data_move_c_pNLRTW551QX6M_: + case data_move_c_pWKYXT98G57H5_: return execEvent9(); - case data_move_c_pZ6VVX7FHA9UC_: + case data_move_c_pYG2W44S9M0LS_: return execEvent10(); case data_needs_ajustment_c_none_: return execEvent11(); diff --git a/scenarios/scenario-6-push-ball-goal/controller/include/controller/controller_engine.h b/scenarios/scenario-6-push-ball-goal/controller/include/controller/controller_engine.h index aaa0548..5cbdd22 100644 --- a/scenarios/scenario-6-push-ball-goal/controller/include/controller/controller_engine.h +++ b/scenarios/scenario-6-push-ball-goal/controller/include/controller/controller_engine.h @@ -15,11 +15,11 @@ enum Enumcontroller_ { _controller_awaiting, _controller_ball_found, _controller_ball_in_front, - _controller_data_p3FWU5LJD83KP, - _controller_data_pT6I8XRJ5MOT3, - _controller_data_pWKTMPZDWUE17, - _controller_data_pZQUQLRDM9OJ6, - _controller_data_pZQUXVJGJO0YV, + _controller_data_p19ECF3KTP0U8, + _controller_data_pCAZ89YPHWXZQ, + _controller_data_pEPMG0RA510TK, + _controller_data_pG91L42WDTXHW, + _controller_data_pHT24JRO2029H, _controller_free, _controller_goal_found, _controller_in_service, @@ -62,13 +62,13 @@ enum controllerEventEnum_ { data_continue_c_none_, /**< Event data_continue.c_none. */ message_move_c_trigger_, /**< Event message_move.c_trigger. */ data_move_c_none_, /**< Event data_move.c_none. */ - data_move_c_pNLRTW551QX6M_, /**< Event data_move.c_pNLRTW551QX6M. */ - data_move_c_pLQBN5IDMMNA0_, /**< Event data_move.c_pLQBN5IDMMNA0. */ - data_move_c_pZ6VVX7FHA9UC_, /**< Event data_move.c_pZ6VVX7FHA9UC. */ - data_move_c_pHKVHWHN6EUM1_, /**< Event data_move.c_pHKVHWHN6EUM1. */ + data_move_c_p0MTC7HSVMD25_, /**< Event data_move.c_p0MTC7HSVMD25. */ + data_move_c_pPLIRMHMV31U1_, /**< Event data_move.c_pPLIRMHMV31U1. */ + data_move_c_pWKYXT98G57H5_, /**< Event data_move.c_pWKYXT98G57H5. */ + data_move_c_pYG2W44S9M0LS_, /**< Event data_move.c_pYG2W44S9M0LS. */ message_halt_c_trigger_, /**< Event message_halt.c_trigger. */ data_halt_c_none_, /**< Event data_halt.c_none. */ - data_halt_c_p7A4YL2QMRJC0_, /**< Event data_halt.c_p7A4YL2QMRJC0. */ + data_halt_c_p9DORKK07C1FW_, /**< Event data_halt.c_p9DORKK07C1FW. */ }; typedef enum controllerEventEnum_ controller_Event_; diff --git a/scenarios/scenario-6-push-ball-goal/controller/src/member_function.cpp b/scenarios/scenario-6-push-ball-goal/controller/src/member_function.cpp index a9e98e3..2fca337 100644 --- a/scenarios/scenario-6-push-ball-goal/controller/src/member_function.cpp +++ b/scenarios/scenario-6-push-ball-goal/controller/src/member_function.cpp @@ -226,19 +226,19 @@ class Controller : public rclcpp::Node { void call_message_move() { auto value = geometry_msgs::msg::Twist(); - if (data_move_ == _controller_data_p3FWU5LJD83KP) { + if (data_move_ == _controller_data_pG91L42WDTXHW) { value.linear.x = 0.2; value.angular.z = (0.0 - code_BallDetector_current_correction) / 500; } else - if (data_move_ == _controller_data_pZQUQLRDM9OJ6) { + if (data_move_ == _controller_data_pEPMG0RA510TK) { value.linear.x = 0.2; value.angular.z = (code_BallDetector_current_correction) / 1000; } else - if (data_move_ == _controller_data_pZQUXVJGJO0YV) { + if (data_move_ == _controller_data_pCAZ89YPHWXZQ) { value.linear.x = 0.2; value.angular.z = (0.0 - code_GoalDetector_current_correction) / 1000; } else - if (data_move_ == _controller_data_pWKTMPZDWUE17) { + if (data_move_ == _controller_data_pHT24JRO2029H) { value.angular.z = 0.5; } @@ -250,7 +250,7 @@ class Controller : public rclcpp::Node { void call_message_halt() { auto value = geometry_msgs::msg::Twist(); - if (data_halt_ == _controller_data_pT6I8XRJ5MOT3) { + if (data_halt_ == _controller_data_p19ECF3KTP0U8) { value.linear.x = 0.0; value.angular.z = 0.0; } @@ -316,7 +316,7 @@ class Controller : public rclcpp::Node { // Heart of the controller void tick() { int nOfDataEvents = 5; - controller_Event_ data_events[5] = { data_move_c_pNLRTW551QX6M_,data_move_c_pLQBN5IDMMNA0_,data_move_c_pZ6VVX7FHA9UC_,data_move_c_pHKVHWHN6EUM1_,data_halt_c_p7A4YL2QMRJC0_ }; + controller_Event_ data_events[5] = { data_move_c_p0MTC7HSVMD25_,data_move_c_pPLIRMHMV31U1_,data_move_c_pWKYXT98G57H5_,data_move_c_pYG2W44S9M0LS_,data_halt_c_p9DORKK07C1FW_ }; // Always execute data transitions that are possible shuffle_events(data_events, nOfDataEvents); @@ -331,7 +331,9 @@ class Controller : public rclcpp::Node { shuffle_events(controllable_events, nOfControllableEvents); for (int i = 0; i < nOfControllableEvents; i++) { - controller_EnginePerformEvent(controllable_events[i]); + if (controller_EnginePerformEvent(controllable_events[i])) { + break; + } } this->emit_current_state(); diff --git a/scenarios/scenario-6-push-ball-goal/push_ball_goal.rscd b/scenarios/scenario-6-push-ball-goal/push_ball_goal.rscd index 3405fec..c05f75c 100644 --- a/scenarios/scenario-6-push-ball-goal/push_ball_goal.rscd +++ b/scenarios/scenario-6-push-ball-goal/push_ball_goal.rscd @@ -16,7 +16,7 @@ robot PushBallGoal { behaviour { variable distance: Distance - initial state sensing { + initial marked state sensing { on response from scan do distance := value } } @@ -44,12 +44,12 @@ robot PushBallGoal { on response from ball_front_check goto ball_in_front } - state no_ball { + marked state no_ball { on response from no_ball goto no_ball on response from ball_correction goto ball_found } - state ball_in_front { + marked state ball_in_front { on response from needs_ajustment goto adjusting } @@ -76,7 +76,7 @@ robot PushBallGoal { on response from goal_correction do current_correction := value } - state no_goal { + marked state no_goal { on response from goal_correction goto goal_found } } diff --git a/scenarios/scenario-7-person-following/controller/include/controller/controller_engine.c b/scenarios/scenario-7-person-following/controller/include/controller/controller_engine.c index 2222b3c..cb7e48b 100644 --- a/scenarios/scenario-7-person-following/controller/include/controller/controller_engine.c +++ b/scenarios/scenario-7-person-following/controller/include/controller/controller_engine.c @@ -45,20 +45,20 @@ const char *controller_event_names[] = { "data_continue.c_none", /**< Event data_continue.c_none. */ "message_move.c_trigger", /**< Event message_move.c_trigger. */ "data_move.c_none", /**< Event data_move.c_none. */ - "data_move.c_pE7UYQJY79SM8", /**< Event data_move.c_pE7UYQJY79SM8. */ - "data_move.c_p4BF22BNB53W7", /**< Event data_move.c_p4BF22BNB53W7. */ - "data_move.c_p3QQTOJTJJA3D", /**< Event data_move.c_p3QQTOJTJJA3D. */ + "data_move.c_pGMPSSSIS1QV7", /**< Event data_move.c_pGMPSSSIS1QV7. */ + "data_move.c_pVDT3GHXV702K", /**< Event data_move.c_pVDT3GHXV702K. */ + "data_move.c_p4XGWRXEQ64QX", /**< Event data_move.c_p4XGWRXEQ64QX. */ "message_halt.c_trigger", /**< Event message_halt.c_trigger. */ "data_halt.c_none", /**< Event data_halt.c_none. */ - "data_halt.c_p3N8RD73YSOWM", /**< Event data_halt.c_p3N8RD73YSOWM. */ + "data_halt.c_pRDQU5M38JY49", /**< Event data_halt.c_pRDQU5M38JY49. */ }; /** Enumeration names. */ const char *enum_names[] = { - "data_p0Q75TJOH95KQ", - "data_pI6051UITZCXO", - "data_pNB5OZ9AD5ICW", - "data_pOEAI5JZDSB7U", + "data_p8OLNEMNMTTVZ", + "data_p8X5ZPW7S5PZD", + "data_pQ489YMH3IPPW", + "data_pV6KEWXT2L92L", "detected", "free", "in_service", @@ -157,26 +157,26 @@ static BoolType execEvent2(void) { } /** - * Execute code for event "data_halt.c_p3N8RD73YSOWM". + * Execute code for event "data_halt.c_pRDQU5M38JY49". * * @return Whether the event was performed. */ static BoolType execEvent3(void) { - BoolType guard = ((data_halt_) == (_controller_none)) || ((data_halt_) == (_controller_data_pI6051UITZCXO)); + BoolType guard = ((data_halt_) == (_controller_none)) || ((data_halt_) == (_controller_data_pV6KEWXT2L92L)); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_halt_c_p3N8RD73YSOWM_, TRUE); + controller_InfoEvent(data_halt_c_pRDQU5M38JY49_, TRUE); #endif if ((data_halt_) == (_controller_none)) { - data_halt_ = _controller_data_pI6051UITZCXO; - } else if ((data_halt_) == (_controller_data_pI6051UITZCXO)) { - data_halt_ = _controller_data_pI6051UITZCXO; + data_halt_ = _controller_data_pV6KEWXT2L92L; + } else if ((data_halt_) == (_controller_data_pV6KEWXT2L92L)) { + data_halt_ = _controller_data_pV6KEWXT2L92L; } #if EVENT_OUTPUT - controller_InfoEvent(data_halt_c_p3N8RD73YSOWM_, FALSE); + controller_InfoEvent(data_halt_c_pRDQU5M38JY49_, FALSE); #endif return TRUE; } @@ -187,7 +187,7 @@ static BoolType execEvent3(void) { * @return Whether the event was performed. */ static BoolType execEvent4(void) { - BoolType guard = (((((data_move_) == (_controller_none)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing)))) || ((((data_move_) == (_controller_data_p0Q75TJOH95KQ)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing))))) || (((((data_move_) == (_controller_data_pOEAI5JZDSB7U)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing)))) || ((((data_move_) == (_controller_data_pNB5OZ9AD5ICW)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing))))); + BoolType guard = (((((data_move_) == (_controller_none)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing)))) || ((((data_move_) == (_controller_data_p8X5ZPW7S5PZD)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing))))) || (((((data_move_) == (_controller_data_pQ489YMH3IPPW)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing)))) || ((((data_move_) == (_controller_data_p8OLNEMNMTTVZ)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing))))); if (!guard) return FALSE; #if EVENT_OUTPUT @@ -196,11 +196,11 @@ static BoolType execEvent4(void) { if ((((data_move_) == (_controller_none)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing)))) { data_move_ = _controller_none; - } else if ((((data_move_) == (_controller_data_p0Q75TJOH95KQ)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing)))) { + } else if ((((data_move_) == (_controller_data_p8X5ZPW7S5PZD)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing)))) { data_move_ = _controller_none; - } else if ((((data_move_) == (_controller_data_pOEAI5JZDSB7U)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing)))) { + } else if ((((data_move_) == (_controller_data_pQ489YMH3IPPW)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing)))) { data_move_ = _controller_none; - } else if ((((data_move_) == (_controller_data_pNB5OZ9AD5ICW)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing)))) { + } else if ((((data_move_) == (_controller_data_p8OLNEMNMTTVZ)) && (!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) && ((!(((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) && ((component_YoloxDetection_ != _controller_initializing)))) { data_move_ = _controller_none; } @@ -211,88 +211,88 @@ static BoolType execEvent4(void) { } /** - * Execute code for event "data_move.c_p3QQTOJTJJA3D". + * Execute code for event "data_move.c_p4XGWRXEQ64QX". * * @return Whether the event was performed. */ static BoolType execEvent5(void) { - BoolType guard = ((((data_move_) == (_controller_none)) && ((component_YoloxDetection_) == (_controller_initializing))) || (((data_move_) == (_controller_data_p0Q75TJOH95KQ)) && ((component_YoloxDetection_) == (_controller_initializing)))) || ((((data_move_) == (_controller_data_pOEAI5JZDSB7U)) && ((component_YoloxDetection_) == (_controller_initializing))) || (((data_move_) == (_controller_data_pNB5OZ9AD5ICW)) && ((component_YoloxDetection_) == (_controller_initializing)))); + BoolType guard = ((((data_move_) == (_controller_none)) && ((component_YoloxDetection_) == (_controller_initializing))) || (((data_move_) == (_controller_data_p8X5ZPW7S5PZD)) && ((component_YoloxDetection_) == (_controller_initializing)))) || ((((data_move_) == (_controller_data_pQ489YMH3IPPW)) && ((component_YoloxDetection_) == (_controller_initializing))) || (((data_move_) == (_controller_data_p8OLNEMNMTTVZ)) && ((component_YoloxDetection_) == (_controller_initializing)))); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_p3QQTOJTJJA3D_, TRUE); + controller_InfoEvent(data_move_c_p4XGWRXEQ64QX_, TRUE); #endif if (((data_move_) == (_controller_none)) && ((component_YoloxDetection_) == (_controller_initializing))) { - data_move_ = _controller_data_pNB5OZ9AD5ICW; - } else if (((data_move_) == (_controller_data_p0Q75TJOH95KQ)) && ((component_YoloxDetection_) == (_controller_initializing))) { - data_move_ = _controller_data_pNB5OZ9AD5ICW; - } else if (((data_move_) == (_controller_data_pOEAI5JZDSB7U)) && ((component_YoloxDetection_) == (_controller_initializing))) { - data_move_ = _controller_data_pNB5OZ9AD5ICW; - } else if (((data_move_) == (_controller_data_pNB5OZ9AD5ICW)) && ((component_YoloxDetection_) == (_controller_initializing))) { - data_move_ = _controller_data_pNB5OZ9AD5ICW; + data_move_ = _controller_data_p8OLNEMNMTTVZ; + } else if (((data_move_) == (_controller_data_p8X5ZPW7S5PZD)) && ((component_YoloxDetection_) == (_controller_initializing))) { + data_move_ = _controller_data_p8OLNEMNMTTVZ; + } else if (((data_move_) == (_controller_data_pQ489YMH3IPPW)) && ((component_YoloxDetection_) == (_controller_initializing))) { + data_move_ = _controller_data_p8OLNEMNMTTVZ; + } else if (((data_move_) == (_controller_data_p8OLNEMNMTTVZ)) && ((component_YoloxDetection_) == (_controller_initializing))) { + data_move_ = _controller_data_p8OLNEMNMTTVZ; } #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_p3QQTOJTJJA3D_, FALSE); + controller_InfoEvent(data_move_c_p4XGWRXEQ64QX_, FALSE); #endif return TRUE; } /** - * Execute code for event "data_move.c_p4BF22BNB53W7". + * Execute code for event "data_move.c_pGMPSSSIS1QV7". * * @return Whether the event was performed. */ static BoolType execEvent6(void) { - BoolType guard = ((((data_move_) == (_controller_none)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) || (((data_move_) == (_controller_data_p0Q75TJOH95KQ)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free))))) || ((((data_move_) == (_controller_data_pOEAI5JZDSB7U)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) || (((data_move_) == (_controller_data_pNB5OZ9AD5ICW)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free))))); + BoolType guard = ((((data_move_) == (_controller_none)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person)))) || (((data_move_) == (_controller_data_p8X5ZPW7S5PZD)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) || ((((data_move_) == (_controller_data_pQ489YMH3IPPW)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person)))) || (((data_move_) == (_controller_data_p8OLNEMNMTTVZ)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_p4BF22BNB53W7_, TRUE); + controller_InfoEvent(data_move_c_pGMPSSSIS1QV7_, TRUE); #endif - if (((data_move_) == (_controller_none)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) { - data_move_ = _controller_data_pOEAI5JZDSB7U; - } else if (((data_move_) == (_controller_data_p0Q75TJOH95KQ)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) { - data_move_ = _controller_data_pOEAI5JZDSB7U; - } else if (((data_move_) == (_controller_data_pOEAI5JZDSB7U)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) { - data_move_ = _controller_data_pOEAI5JZDSB7U; - } else if (((data_move_) == (_controller_data_pNB5OZ9AD5ICW)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) { - data_move_ = _controller_data_pOEAI5JZDSB7U; + if (((data_move_) == (_controller_none)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person)))) { + data_move_ = _controller_data_p8X5ZPW7S5PZD; + } else if (((data_move_) == (_controller_data_p8X5ZPW7S5PZD)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person)))) { + data_move_ = _controller_data_p8X5ZPW7S5PZD; + } else if (((data_move_) == (_controller_data_pQ489YMH3IPPW)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person)))) { + data_move_ = _controller_data_p8X5ZPW7S5PZD; + } else if (((data_move_) == (_controller_data_p8OLNEMNMTTVZ)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person)))) { + data_move_ = _controller_data_p8X5ZPW7S5PZD; } #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_p4BF22BNB53W7_, FALSE); + controller_InfoEvent(data_move_c_pGMPSSSIS1QV7_, FALSE); #endif return TRUE; } /** - * Execute code for event "data_move.c_pE7UYQJY79SM8". + * Execute code for event "data_move.c_pVDT3GHXV702K". * * @return Whether the event was performed. */ static BoolType execEvent7(void) { - BoolType guard = ((((data_move_) == (_controller_none)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person)))) || (((data_move_) == (_controller_data_p0Q75TJOH95KQ)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))) || ((((data_move_) == (_controller_data_pOEAI5JZDSB7U)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person)))) || (((data_move_) == (_controller_data_pNB5OZ9AD5ICW)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person))))); + BoolType guard = ((((data_move_) == (_controller_none)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) || (((data_move_) == (_controller_data_p8X5ZPW7S5PZD)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free))))) || ((((data_move_) == (_controller_data_pQ489YMH3IPPW)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) || (((data_move_) == (_controller_data_p8OLNEMNMTTVZ)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free))))); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_pE7UYQJY79SM8_, TRUE); + controller_InfoEvent(data_move_c_pVDT3GHXV702K_, TRUE); #endif - if (((data_move_) == (_controller_none)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person)))) { - data_move_ = _controller_data_p0Q75TJOH95KQ; - } else if (((data_move_) == (_controller_data_p0Q75TJOH95KQ)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person)))) { - data_move_ = _controller_data_p0Q75TJOH95KQ; - } else if (((data_move_) == (_controller_data_pOEAI5JZDSB7U)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person)))) { - data_move_ = _controller_data_p0Q75TJOH95KQ; - } else if (((data_move_) == (_controller_data_pNB5OZ9AD5ICW)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_person)))) { - data_move_ = _controller_data_p0Q75TJOH95KQ; + if (((data_move_) == (_controller_none)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) { + data_move_ = _controller_data_pQ489YMH3IPPW; + } else if (((data_move_) == (_controller_data_p8X5ZPW7S5PZD)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) { + data_move_ = _controller_data_pQ489YMH3IPPW; + } else if (((data_move_) == (_controller_data_pQ489YMH3IPPW)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) { + data_move_ = _controller_data_pQ489YMH3IPPW; + } else if (((data_move_) == (_controller_data_p8OLNEMNMTTVZ)) && (((component_YoloxDetection_) == (_controller_detected)) && ((component_Scanner_v_distance_) == (_controller_free)))) { + data_move_ = _controller_data_pQ489YMH3IPPW; } #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_pE7UYQJY79SM8_, FALSE); + controller_InfoEvent(data_move_c_pVDT3GHXV702K_, FALSE); #endif return TRUE; } @@ -504,11 +504,11 @@ static void PerformEvents(void) { if (execEvent0()) continue; /* (Try to) perform event "data_bounding_boxes.c_none". */ if (execEvent1()) continue; /* (Try to) perform event "data_continue.c_none". */ if (execEvent2()) continue; /* (Try to) perform event "data_halt.c_none". */ - if (execEvent3()) continue; /* (Try to) perform event "data_halt.c_p3N8RD73YSOWM". */ + if (execEvent3()) continue; /* (Try to) perform event "data_halt.c_pRDQU5M38JY49". */ if (execEvent4()) continue; /* (Try to) perform event "data_move.c_none". */ - if (execEvent5()) continue; /* (Try to) perform event "data_move.c_p3QQTOJTJJA3D". */ - if (execEvent6()) continue; /* (Try to) perform event "data_move.c_p4BF22BNB53W7". */ - if (execEvent7()) continue; /* (Try to) perform event "data_move.c_pE7UYQJY79SM8". */ + if (execEvent5()) continue; /* (Try to) perform event "data_move.c_p4XGWRXEQ64QX". */ + if (execEvent6()) continue; /* (Try to) perform event "data_move.c_pGMPSSSIS1QV7". */ + if (execEvent7()) continue; /* (Try to) perform event "data_move.c_pVDT3GHXV702K". */ if (execEvent8()) continue; /* (Try to) perform event "data_scan.c_none". */ if (execEvent9()) continue; /* (Try to) perform event "data_stop.c_none". */ if (execEvent12()) continue; /* (Try to) perform event "message_halt.c_trigger". */ @@ -582,15 +582,15 @@ BoolType controller_EnginePerformEvent(controller_Event_ event) { return execEvent1(); case data_halt_c_none_: return execEvent2(); - case data_halt_c_p3N8RD73YSOWM_: + case data_halt_c_pRDQU5M38JY49_: return execEvent3(); case data_move_c_none_: return execEvent4(); - case data_move_c_p3QQTOJTJJA3D_: + case data_move_c_p4XGWRXEQ64QX_: return execEvent5(); - case data_move_c_p4BF22BNB53W7_: + case data_move_c_pGMPSSSIS1QV7_: return execEvent6(); - case data_move_c_pE7UYQJY79SM8_: + case data_move_c_pVDT3GHXV702K_: return execEvent7(); case data_scan_c_none_: return execEvent8(); diff --git a/scenarios/scenario-7-person-following/controller/include/controller/controller_engine.h b/scenarios/scenario-7-person-following/controller/include/controller/controller_engine.h index 56b2ece..15f1d23 100644 --- a/scenarios/scenario-7-person-following/controller/include/controller/controller_engine.h +++ b/scenarios/scenario-7-person-following/controller/include/controller/controller_engine.h @@ -11,10 +11,10 @@ * Note that integer ranges are ignored in C. */ enum Enumcontroller_ { - _controller_data_p0Q75TJOH95KQ, - _controller_data_pI6051UITZCXO, - _controller_data_pNB5OZ9AD5ICW, - _controller_data_pOEAI5JZDSB7U, + _controller_data_p8OLNEMNMTTVZ, + _controller_data_p8X5ZPW7S5PZD, + _controller_data_pQ489YMH3IPPW, + _controller_data_pV6KEWXT2L92L, _controller_detected, _controller_free, _controller_in_service, @@ -44,12 +44,12 @@ enum controllerEventEnum_ { data_continue_c_none_, /**< Event data_continue.c_none. */ message_move_c_trigger_, /**< Event message_move.c_trigger. */ data_move_c_none_, /**< Event data_move.c_none. */ - data_move_c_pE7UYQJY79SM8_, /**< Event data_move.c_pE7UYQJY79SM8. */ - data_move_c_p4BF22BNB53W7_, /**< Event data_move.c_p4BF22BNB53W7. */ - data_move_c_p3QQTOJTJJA3D_, /**< Event data_move.c_p3QQTOJTJJA3D. */ + data_move_c_pGMPSSSIS1QV7_, /**< Event data_move.c_pGMPSSSIS1QV7. */ + data_move_c_pVDT3GHXV702K_, /**< Event data_move.c_pVDT3GHXV702K. */ + data_move_c_p4XGWRXEQ64QX_, /**< Event data_move.c_p4XGWRXEQ64QX. */ message_halt_c_trigger_, /**< Event message_halt.c_trigger. */ data_halt_c_none_, /**< Event data_halt.c_none. */ - data_halt_c_p3N8RD73YSOWM_, /**< Event data_halt.c_p3N8RD73YSOWM. */ + data_halt_c_pRDQU5M38JY49_, /**< Event data_halt.c_pRDQU5M38JY49. */ }; typedef enum controllerEventEnum_ controller_Event_; diff --git a/scenarios/scenario-7-person-following/controller/src/member_function.cpp b/scenarios/scenario-7-person-following/controller/src/member_function.cpp index 685671f..21dba5e 100644 --- a/scenarios/scenario-7-person-following/controller/src/member_function.cpp +++ b/scenarios/scenario-7-person-following/controller/src/member_function.cpp @@ -157,15 +157,15 @@ class Controller : public rclcpp::Node { void call_message_move() { auto value = geometry_msgs::msg::Twist(); - if (data_move_ == _controller_data_p0Q75TJOH95KQ) { + if (data_move_ == _controller_data_p8X5ZPW7S5PZD) { value.linear.x = 0.0; value.angular.z = ((code_YoloxDetection_current_image_size / 2) - ((code_YoloxDetection_current_xmin + code_YoloxDetection_current_xmax) / 2)) / 1000; } else - if (data_move_ == _controller_data_pOEAI5JZDSB7U) { + if (data_move_ == _controller_data_pQ489YMH3IPPW) { value.linear.x = 0.2; value.angular.z = ((code_YoloxDetection_current_image_size / 2) - ((code_YoloxDetection_current_xmin + code_YoloxDetection_current_xmax) / 2)) / 1000; } else - if (data_move_ == _controller_data_pNB5OZ9AD5ICW) { + if (data_move_ == _controller_data_p8OLNEMNMTTVZ) { value.linear.x = 0.0; value.angular.z = 0.3; } @@ -178,7 +178,7 @@ class Controller : public rclcpp::Node { void call_message_halt() { auto value = geometry_msgs::msg::Twist(); - if (data_halt_ == _controller_data_pI6051UITZCXO) { + if (data_halt_ == _controller_data_pV6KEWXT2L92L) { value.linear.x = 0.0; value.angular.z = 0.0; } @@ -238,7 +238,7 @@ class Controller : public rclcpp::Node { // Heart of the controller void tick() { int nOfDataEvents = 4; - controller_Event_ data_events[4] = { data_move_c_pE7UYQJY79SM8_,data_move_c_p4BF22BNB53W7_,data_move_c_p3QQTOJTJJA3D_,data_halt_c_p3N8RD73YSOWM_ }; + controller_Event_ data_events[4] = { data_move_c_pGMPSSSIS1QV7_,data_move_c_pVDT3GHXV702K_,data_move_c_p4XGWRXEQ64QX_,data_halt_c_pRDQU5M38JY49_ }; // Always execute data transitions that are possible shuffle_events(data_events, nOfDataEvents); @@ -253,7 +253,9 @@ class Controller : public rclcpp::Node { shuffle_events(controllable_events, nOfControllableEvents); for (int i = 0; i < nOfControllableEvents; i++) { - controller_EnginePerformEvent(controllable_events[i]); + if (controller_EnginePerformEvent(controllable_events[i])) { + break; + } } this->emit_current_state(); diff --git a/scenarios/scenario-7-person-following/person_following.rscd b/scenarios/scenario-7-person-following/person_following.rscd index 26da214..3766d6e 100644 --- a/scenarios/scenario-7-person-following/person_following.rscd +++ b/scenarios/scenario-7-person-following/person_following.rscd @@ -27,7 +27,7 @@ robot PersonFollowing { behaviour { variable distance: Distance - initial state sensing { + initial marked state sensing { on response from scan do distance := value } } @@ -47,7 +47,7 @@ robot PersonFollowing { goto detected initial state initializing {} - state detected {} + marked state detected {} } } diff --git a/scenarios/scenario-8-supervisor/line_follower_supervisor.rscd b/scenarios/scenario-8-supervisor/line_follower_supervisor.rscd index 1baee5d..186920f 100644 --- a/scenarios/scenario-8-supervisor/line_follower_supervisor.rscd +++ b/scenarios/scenario-8-supervisor/line_follower_supervisor.rscd @@ -20,7 +20,7 @@ robot LineFollowerSupervised { behaviour { variable current_correction: double = 0.0 - initial state no_line { + initial marked state no_line { on response from correction goto line_found } @@ -48,7 +48,7 @@ robot LineFollowerSupervised { on response from scan do current_distance := value - initial state unsafe_distance { + initial marked state unsafe_distance { transition if current_distance = safe goto safe_distance } diff --git a/scenarios/scenario-8-supervisor/supervisor/include/controller/controller_engine.c b/scenarios/scenario-8-supervisor/supervisor/include/controller/controller_engine.c index 08ed539..885b692 100644 --- a/scenarios/scenario-8-supervisor/supervisor/include/controller/controller_engine.c +++ b/scenarios/scenario-8-supervisor/supervisor/include/controller/controller_engine.c @@ -39,13 +39,13 @@ const char *controller_event_names[] = { "data_correction.c_none", /**< Event data_correction.c_none. */ "message_no_line.u_response", /**< Event message_no_line.u_response. */ "data_no_line.c_none", /**< Event data_no_line.c_none. */ - "component_LidarSensor.c_p6IKBNCE0CF2A", /**< Event component_LidarSensor.c_p6IKBNCE0CF2A. */ - "component_LidarSensor.c_pGNFFIMP7J5DD", /**< Event component_LidarSensor.c_pGNFFIMP7J5DD. */ + "component_LidarSensor.c_p86NQIBI9OXR9", /**< Event component_LidarSensor.c_p86NQIBI9OXR9. */ + "component_LidarSensor.c_pH46TBIXUK413", /**< Event component_LidarSensor.c_pH46TBIXUK413. */ "message_scan.u_response", /**< Event message_scan.u_response. */ "data_scan.c_none", /**< Event data_scan.c_none. */ "message_move.c_trigger", /**< Event message_move.c_trigger. */ "data_move.c_none", /**< Event data_move.c_none. */ - "data_move.c_pK6XY8M2QGABW", /**< Event data_move.c_pK6XY8M2QGABW. */ + "data_move.c_pVTI0LIP3AUDS", /**< Event data_move.c_pVTI0LIP3AUDS. */ "message_stop.u_response", /**< Event message_stop.u_response. */ "data_stop.c_none", /**< Event data_stop.c_none. */ "message_continue.u_response", /**< Event message_continue.u_response. */ @@ -54,7 +54,7 @@ const char *controller_event_names[] = { /** Enumeration names. */ const char *enum_names[] = { - "data_p7H2JXWWT4LDZ", + "data_pIV8Z8BIYO3SS", "in_service", "line_found", "no_line", @@ -98,7 +98,7 @@ static void PrintOutput(controller_Event_ event, BoolType pre) { /* Event execution code. */ /** - * Execute code for event "component_LidarSensor.c_p6IKBNCE0CF2A". + * Execute code for event "component_LidarSensor.c_p86NQIBI9OXR9". * * @return Whether the event was performed. */ @@ -107,19 +107,19 @@ static BoolType execEvent0(void) { if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(component_LidarSensor_c_p6IKBNCE0CF2A_, TRUE); + controller_InfoEvent(component_LidarSensor_c_p86NQIBI9OXR9_, TRUE); #endif component_LidarSensor_ = _controller_safe_distance; #if EVENT_OUTPUT - controller_InfoEvent(component_LidarSensor_c_p6IKBNCE0CF2A_, FALSE); + controller_InfoEvent(component_LidarSensor_c_p86NQIBI9OXR9_, FALSE); #endif return TRUE; } /** - * Execute code for event "component_LidarSensor.c_pGNFFIMP7J5DD". + * Execute code for event "component_LidarSensor.c_pH46TBIXUK413". * * @return Whether the event was performed. */ @@ -128,13 +128,13 @@ static BoolType execEvent1(void) { if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(component_LidarSensor_c_pGNFFIMP7J5DD_, TRUE); + controller_InfoEvent(component_LidarSensor_c_pH46TBIXUK413_, TRUE); #endif component_LidarSensor_ = _controller_unsafe_distance; #if EVENT_OUTPUT - controller_InfoEvent(component_LidarSensor_c_pGNFFIMP7J5DD_, FALSE); + controller_InfoEvent(component_LidarSensor_c_pH46TBIXUK413_, FALSE); #endif return TRUE; } @@ -197,26 +197,26 @@ static BoolType execEvent4(void) { } /** - * Execute code for event "data_move.c_pK6XY8M2QGABW". + * Execute code for event "data_move.c_pVTI0LIP3AUDS". * * @return Whether the event was performed. */ static BoolType execEvent5(void) { - BoolType guard = ((data_move_) == (_controller_none)) || ((data_move_) == (_controller_data_p7H2JXWWT4LDZ)); + BoolType guard = ((data_move_) == (_controller_none)) || ((data_move_) == (_controller_data_pIV8Z8BIYO3SS)); if (!guard) return FALSE; #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_pK6XY8M2QGABW_, TRUE); + controller_InfoEvent(data_move_c_pVTI0LIP3AUDS_, TRUE); #endif if ((data_move_) == (_controller_none)) { - data_move_ = _controller_data_p7H2JXWWT4LDZ; - } else if ((data_move_) == (_controller_data_p7H2JXWWT4LDZ)) { - data_move_ = _controller_data_p7H2JXWWT4LDZ; + data_move_ = _controller_data_pIV8Z8BIYO3SS; + } else if ((data_move_) == (_controller_data_pIV8Z8BIYO3SS)) { + data_move_ = _controller_data_pIV8Z8BIYO3SS; } #if EVENT_OUTPUT - controller_InfoEvent(data_move_c_pK6XY8M2QGABW_, FALSE); + controller_InfoEvent(data_move_c_pVTI0LIP3AUDS_, FALSE); #endif return TRUE; } @@ -451,12 +451,12 @@ static void PerformEvents(void) { break; } - if (execEvent0()) continue; /* (Try to) perform event "component_LidarSensor.c_p6IKBNCE0CF2A". */ - if (execEvent1()) continue; /* (Try to) perform event "component_LidarSensor.c_pGNFFIMP7J5DD". */ + if (execEvent0()) continue; /* (Try to) perform event "component_LidarSensor.c_p86NQIBI9OXR9". */ + if (execEvent1()) continue; /* (Try to) perform event "component_LidarSensor.c_pH46TBIXUK413". */ if (execEvent2()) continue; /* (Try to) perform event "data_continue.c_none". */ if (execEvent3()) continue; /* (Try to) perform event "data_correction.c_none". */ if (execEvent4()) continue; /* (Try to) perform event "data_move.c_none". */ - if (execEvent5()) continue; /* (Try to) perform event "data_move.c_pK6XY8M2QGABW". */ + if (execEvent5()) continue; /* (Try to) perform event "data_move.c_pVTI0LIP3AUDS". */ if (execEvent6()) continue; /* (Try to) perform event "data_no_line.c_none". */ if (execEvent7()) continue; /* (Try to) perform event "data_scan.c_none". */ if (execEvent8()) continue; /* (Try to) perform event "data_stop.c_none". */ @@ -524,9 +524,9 @@ void controller_EngineTimeStep(double delta) { */ BoolType controller_EnginePerformEvent(controller_Event_ event) { switch (event) { - case component_LidarSensor_c_p6IKBNCE0CF2A_: + case component_LidarSensor_c_p86NQIBI9OXR9_: return execEvent0(); - case component_LidarSensor_c_pGNFFIMP7J5DD_: + case component_LidarSensor_c_pH46TBIXUK413_: return execEvent1(); case data_continue_c_none_: return execEvent2(); @@ -534,7 +534,7 @@ BoolType controller_EnginePerformEvent(controller_Event_ event) { return execEvent3(); case data_move_c_none_: return execEvent4(); - case data_move_c_pK6XY8M2QGABW_: + case data_move_c_pVTI0LIP3AUDS_: return execEvent5(); case data_no_line_c_none_: return execEvent6(); diff --git a/scenarios/scenario-8-supervisor/supervisor/include/controller/controller_engine.h b/scenarios/scenario-8-supervisor/supervisor/include/controller/controller_engine.h index 9fd01b2..0bb14ee 100644 --- a/scenarios/scenario-8-supervisor/supervisor/include/controller/controller_engine.h +++ b/scenarios/scenario-8-supervisor/supervisor/include/controller/controller_engine.h @@ -11,7 +11,7 @@ * Note that integer ranges are ignored in C. */ enum Enumcontroller_ { - _controller_data_p7H2JXWWT4LDZ, + _controller_data_pIV8Z8BIYO3SS, _controller_in_service, _controller_line_found, _controller_no_line, @@ -37,13 +37,13 @@ enum controllerEventEnum_ { data_correction_c_none_, /**< Event data_correction.c_none. */ message_no_line_u_response_, /**< Event message_no_line.u_response. */ data_no_line_c_none_, /**< Event data_no_line.c_none. */ - component_LidarSensor_c_p6IKBNCE0CF2A_, /**< Event component_LidarSensor.c_p6IKBNCE0CF2A. */ - component_LidarSensor_c_pGNFFIMP7J5DD_, /**< Event component_LidarSensor.c_pGNFFIMP7J5DD. */ + component_LidarSensor_c_p86NQIBI9OXR9_, /**< Event component_LidarSensor.c_p86NQIBI9OXR9. */ + component_LidarSensor_c_pH46TBIXUK413_, /**< Event component_LidarSensor.c_pH46TBIXUK413. */ message_scan_u_response_, /**< Event message_scan.u_response. */ data_scan_c_none_, /**< Event data_scan.c_none. */ message_move_c_trigger_, /**< Event message_move.c_trigger. */ data_move_c_none_, /**< Event data_move.c_none. */ - data_move_c_pK6XY8M2QGABW_, /**< Event data_move.c_pK6XY8M2QGABW. */ + data_move_c_pVTI0LIP3AUDS_, /**< Event data_move.c_pVTI0LIP3AUDS. */ message_stop_u_response_, /**< Event message_stop.u_response. */ data_stop_c_none_, /**< Event data_stop.c_none. */ message_continue_u_response_, /**< Event message_continue.u_response. */ diff --git a/scenarios/scenario-8-supervisor/supervisor/launch/supervisor_with_controller.launch.py b/scenarios/scenario-8-supervisor/supervisor/launch/supervisor_with_controller.launch.py index abe25cf..f39242e 100644 --- a/scenarios/scenario-8-supervisor/supervisor/launch/supervisor_with_controller.launch.py +++ b/scenarios/scenario-8-supervisor/supervisor/launch/supervisor_with_controller.launch.py @@ -8,12 +8,12 @@ def generate_launch_description(): remappings = [ - ("/correction", "/correction_pD03NAUQLGW9U"), - ("/no_line", "/no_line_pPWS7VOXLHSV1"), - ("/scan", "/scan_pLGJ50J0RL33J"), - ("/simple_movement", "/simple_movement_pNGAJWRO2BE69"), - ("/stop", "/stop_pO55LCZMBJI3R"), - ("/continue", "/continue_pE153PVY940FM"), + ("/correction", "/correction_p7PRNQJ53OH1G"), + ("/no_line", "/no_line_pNTO0V7A8NW2W"), + ("/scan", "/scan_pV4REPE6TL8AC"), + ("/simple_movement", "/simple_movement_p3KAN9HMKYC27"), + ("/stop", "/stop_pS5SS07H3L3YR"), + ("/continue", "/continue_p0GQQSL4MR92X"), ] return LaunchDescription([ diff --git a/scenarios/scenario-8-supervisor/supervisor/src/member_function.cpp b/scenarios/scenario-8-supervisor/supervisor/src/member_function.cpp index 8ff4c96..07c87c3 100644 --- a/scenarios/scenario-8-supervisor/supervisor/src/member_function.cpp +++ b/scenarios/scenario-8-supervisor/supervisor/src/member_function.cpp @@ -99,17 +99,17 @@ class Supervisor : public rclcpp::Node { std::vector taken_transitions; Supervisor() : Node("supervisor") { - supervised_subscriber_client_correction = this->create_publisher("/correction_pD03NAUQLGW9U", 10); + supervised_subscriber_client_correction = this->create_publisher("/correction_p7PRNQJ53OH1G", 10); subscriber_client_correction = this->create_subscription("/correction", 10, std::bind(&Supervisor::callback_message_correction, this, std::placeholders::_1)); - supervised_subscriber_client_no_line = this->create_publisher("/no_line_pPWS7VOXLHSV1", 10); + supervised_subscriber_client_no_line = this->create_publisher("/no_line_pNTO0V7A8NW2W", 10); subscriber_client_no_line = this->create_subscription("/no_line", 10, std::bind(&Supervisor::callback_message_no_line, this, std::placeholders::_1)); - supervised_subscriber_client_scan = this->create_publisher("/scan_pLGJ50J0RL33J", 10); + supervised_subscriber_client_scan = this->create_publisher("/scan_pV4REPE6TL8AC", 10); subscriber_client_scan = this->create_subscription("/scan", 10, std::bind(&Supervisor::callback_message_scan, this, std::placeholders::_1)); - supervised_publisher_client_move = this->create_subscription("/simple_movement_pNGAJWRO2BE69", 10, std::bind(&Supervisor::callback_message_move_supervised, this, std::placeholders::_1)); + supervised_publisher_client_move = this->create_subscription("/simple_movement_p3KAN9HMKYC27", 10, std::bind(&Supervisor::callback_message_move_supervised, this, std::placeholders::_1)); publisher_client_move = this->create_publisher("/simple_movement", 10); - supervised_subscriber_client_stop = this->create_publisher("/stop_pO55LCZMBJI3R", 10); + supervised_subscriber_client_stop = this->create_publisher("/stop_pS5SS07H3L3YR", 10); subscriber_client_stop = this->create_subscription("/stop", 10, std::bind(&Supervisor::callback_message_stop, this, std::placeholders::_1)); - supervised_subscriber_client_continue = this->create_publisher("/continue_pE153PVY940FM", 10); + supervised_subscriber_client_continue = this->create_publisher("/continue_p0GQQSL4MR92X", 10); subscriber_client_continue = this->create_subscription("/continue", 10, std::bind(&Supervisor::callback_message_continue, this, std::placeholders::_1)); blocked = this->create_publisher("/blocked", 10); @@ -243,7 +243,7 @@ class Supervisor : public rclcpp::Node { output << "}"; output << "},"; output << "\"transitions\": " << serialize_json_vector(taken_transitions) << ","; - output << "\"definition\": " << "{\"name\":\"LineFollowerSupervised\",\"components\":[{\"name\":\"LineDetector\",\"messages\":[\"correction\",\"no_line\"],\"services\":[],\"actions\":[],\"behaviour\":{\"variables\":[\"current_correction\"],\"states\":[{\"name\":\"no_line\",\"initial\":true,\"transitions\":[{\"next\":\"line_found\",\"id\":\"message_correction_u_response_\",\"type\":\"response\",\"communication\":\"correction\"}]},{\"name\":\"line_found\",\"initial\":false,\"transitions\":[{\"next\":\"no_line\",\"id\":\"message_no_line_u_response_\",\"type\":\"response\",\"communication\":\"no_line\"},{\"next\":null,\"id\":\"message_correction_u_response_\",\"type\":\"response\",\"communication\":\"correction\"}]}]}},{\"name\":\"LidarSensor\",\"messages\":[\"scan\"],\"services\":[],\"actions\":[],\"behaviour\":{\"variables\":[\"current_distance\"],\"states\":[{\"name\":\"unsafe_distance\",\"initial\":true,\"transitions\":[{\"next\":\"safe_distance\",\"id\":\"component_LidarSensor_c_p6IKBNCE0CF2A_\",\"type\":\"tau\"},{\"next\":null,\"id\":\"message_scan_u_response_\",\"type\":\"response\",\"communication\":\"scan\"}]},{\"name\":\"safe_distance\",\"initial\":false,\"transitions\":[{\"next\":\"unsafe_distance\",\"id\":\"component_LidarSensor_c_pGNFFIMP7J5DD_\",\"type\":\"tau\"},{\"next\":null,\"id\":\"message_scan_u_response_\",\"type\":\"response\",\"communication\":\"scan\"}]}]}},{\"name\":\"SimpleMovement\",\"messages\":[\"move\"],\"services\":[],\"actions\":[]},{\"name\":\"EmergencyStop\",\"messages\":[\"stop\",\"continue\"],\"services\":[],\"actions\":[],\"behaviour\":{\"variables\":[],\"states\":[{\"name\":\"in_service\",\"initial\":true,\"transitions\":[{\"next\":\"stopped\",\"id\":\"message_stop_u_response_\",\"type\":\"response\",\"communication\":\"stop\"}]},{\"name\":\"stopped\",\"initial\":false,\"transitions\":[{\"next\":\"in_service\",\"id\":\"message_continue_u_response_\",\"type\":\"response\",\"communication\":\"continue\"}]}]}}]}"; + output << "\"definition\": " << "{\"name\":\"LineFollowerSupervised\",\"components\":[{\"name\":\"LineDetector\",\"messages\":[\"correction\",\"no_line\"],\"services\":[],\"actions\":[],\"behaviour\":{\"variables\":[\"current_correction\"],\"states\":[{\"name\":\"no_line\",\"initial\":true,\"transitions\":[{\"next\":\"line_found\",\"id\":\"message_correction_u_response_\",\"type\":\"response\",\"communication\":\"correction\"}]},{\"name\":\"line_found\",\"initial\":false,\"transitions\":[{\"next\":\"no_line\",\"id\":\"message_no_line_u_response_\",\"type\":\"response\",\"communication\":\"no_line\"},{\"next\":null,\"id\":\"message_correction_u_response_\",\"type\":\"response\",\"communication\":\"correction\"}]}]}},{\"name\":\"LidarSensor\",\"messages\":[\"scan\"],\"services\":[],\"actions\":[],\"behaviour\":{\"variables\":[\"current_distance\"],\"states\":[{\"name\":\"unsafe_distance\",\"initial\":true,\"transitions\":[{\"next\":\"safe_distance\",\"id\":\"component_LidarSensor_c_p86NQIBI9OXR9_\",\"type\":\"tau\"},{\"next\":null,\"id\":\"message_scan_u_response_\",\"type\":\"response\",\"communication\":\"scan\"}]},{\"name\":\"safe_distance\",\"initial\":false,\"transitions\":[{\"next\":\"unsafe_distance\",\"id\":\"component_LidarSensor_c_pH46TBIXUK413_\",\"type\":\"tau\"},{\"next\":null,\"id\":\"message_scan_u_response_\",\"type\":\"response\",\"communication\":\"scan\"}]}]}},{\"name\":\"SimpleMovement\",\"messages\":[\"move\"],\"services\":[],\"actions\":[]},{\"name\":\"EmergencyStop\",\"messages\":[\"stop\",\"continue\"],\"services\":[],\"actions\":[],\"behaviour\":{\"variables\":[],\"states\":[{\"name\":\"in_service\",\"initial\":true,\"transitions\":[{\"next\":\"stopped\",\"id\":\"message_stop_u_response_\",\"type\":\"response\",\"communication\":\"stop\"}]},{\"name\":\"stopped\",\"initial\":false,\"transitions\":[{\"next\":\"in_service\",\"id\":\"message_continue_u_response_\",\"type\":\"response\",\"communication\":\"continue\"}]}]}}]}"; output << "}"; auto msg = std_msgs::msg::String(); @@ -265,7 +265,7 @@ class Supervisor : public rclcpp::Node { void execute_all_silent() { int nOfControllableEvents = 2; - controller_Event_ controllable_events[2] = { component_LidarSensor_c_p6IKBNCE0CF2A_,component_LidarSensor_c_pGNFFIMP7J5DD_ }; + controller_Event_ controllable_events[2] = { component_LidarSensor_c_p86NQIBI9OXR9_,component_LidarSensor_c_pH46TBIXUK413_ }; shuffle_events(controllable_events, nOfControllableEvents); diff --git a/scenarios/shared/emergency_stop_library.rscd b/scenarios/shared/emergency_stop_library.rscd index b96f170..84d56fc 100644 --- a/scenarios/shared/emergency_stop_library.rscd +++ b/scenarios/shared/emergency_stop_library.rscd @@ -4,7 +4,7 @@ library EmergencyStopLibrary { outgoing message continue with identifier: "/continue", type: none behaviour { - initial state in_service { + initial marked state in_service { on response from stop goto stopped }