From 1052ecc0e8608eb518cd678ca193115f5f0ddf9f Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Wed, 9 Nov 2016 11:47:11 -0500 Subject: [PATCH 01/13] Define external life cycle management interface --- articles/node_lifecycle.md | 211 +++++++++++++++++++++++++++++++++---- 1 file changed, 188 insertions(+), 23 deletions(-) diff --git a/articles/node_lifecycle.md b/articles/node_lifecycle.md index d6e0715f6..653182f0d 100644 --- a/articles/node_lifecycle.md +++ b/articles/node_lifecycle.md @@ -209,38 +209,203 @@ This transition will instantiate the node, but will not run any code beyond the ## Management Interface -A managed node will be exposed to the ROS ecosystem by the following interface, as seen by tools that perform the managing. -This interface should not be subject to the restrictions on communications imposed by the lifecycle states. +A node that has a managed life cycle complying with the above life cycle shall provide the following interface via ROS topics and services. +This interface is to be used by tools to manage the node's life cycle state transitions, either automatically or manually according to the tool's purpose. -It is expected that a common pattern will be to have a container class which loads a managed node implementation from a library and through a plugin architecture automatically exposes the required management interface via methods and the container is not subject to the lifecycle management. -However, it is fully valid to consider any implementation which provides this interface and follows the lifecycle policies a managed node. -Conversely, any object that provides these services but does not behave in the way defined in the life cycle state machine is malformed. +The topics and services of this interface shall function in all states of the node's life cycle. +They shall not be disabled by the node shifting to the `Inactive` state, for example. + +### Interface namespace + +The interface shall be provided in a namespace named "infra/lifecycle" underneath the node's namespace. + +For example, if a node named `talker` has a managed life cycle complying with the state machine described above, it shall provide topics under the namespace `/talker/infra/lifecycle`. + +All examples in the following sections are also given assuming a node named `talker`. + +If the `infra/lifecycle` namespace is available under a node's namespace, then that node shall be assumed to be functioning according to the managed life cycle. +If the node is not functioning according to the managed life cycle, the `infra/lifecycle` namespace shall not exist. +In other words, tooling shall judge if a node is managed or not by the presence of the `infra/lifecycle` namespace. + +### State enumerations + +The messages used by the interface shall use the following enumeration for indicating states. + + uint8 UNKNOWN=0 + uint8 UNCONFIGURED=1 + uint8 INACTIVE=2 + uint8 ACTIVE=3 + uint8 FINALIZED=4 + uint8 CONFIGURING=10 + uint8 CLEANING_UP=11 + uint8 SHUTTING_DOWN=12 + uint8 ACTIVATING=13 + uint8 DEACTIVATING=14 + uint8 ERROR_PROCESSING=15 + +### Transition result enumerations + +The messages used by the interface shall use the following enumeration for indicating the result of transitions. + + uint8 TRANSITION_ERROR=0 + uint8 SUCCESS=1 + uint8 WRONG_PREV_STATE=10 + +### Life cycle state changes topic + +When the node's life cycle changes, it shall broadcast the following message on the `infra/lifecycle/state_change` topic. + + uint8 previous_state + uint8 next_state + string trigger + +`trigger` may be filled in containing a reason for the life cycle change. This value is optional. + +This topic must be latched. A history of a suitable length should be provided. + +For example, if the `talker` node transitions from the `Active` state to the `Finalised` state via the `ShuttingDown` state in response to an external request to shut down the node, it will produce the following sequence of messages on this topic (values for `trigger` are illustrative only): + + previous_state = INACTIVE + next_state = SHUTTTING_DOWN + trigger = "shutdown request" + + previous_state = SHUTTING_DOWN + next_state = FINALIZED + trigger = "shutdown returned OK" + +If the `talker` node transitions from the `Inactive` state to the `Unconfigured` state via a request to activate the node and an error occurring in activation processing, it will produce the following sequence of messages: + + previous_state = INACTIVE + next_state = ACTIVATING + trigger = "activate request" + + previous_state = ACTIVATING + next_state = ERROR_PROCESSING + trigger = "error in activating state" + + previous_state = ERROR_PROCESSING + next_state = UNCONFIGURED + trigger = "error processing returned OK" + +### Current life cycle state service + +The node's current life cycle state shall be available via the `infra/lifecycle/get_state` service. +The service definition is: + + --- + uint8 state + string state_name + +`state_name` must assume one of the following values, according to the value of `state`. + + Value of state | Value of state_name + UNKNOWN | unknown + UNCONFIGURED | unconfigured + INACTIVE | inactive + ACTIVE | active + FINALIZED | finalized + CONFIGURING | configuring + CLEANING_UP | cleaning_up + SHUTTING_DOWN | shutting_down + ACTIVATING | activating + DEACTIVATING | deactivating + ERROR_PROCESSING | error_processing + +The `UNKNOWN`/`unknown` value shall be assumed by clients of the service to indicate that the node is in an unknown state and thus unusable. + +### Configure transition request service + +The service `infra/lifecycle/configure` service shall be provided by the life cycle interface. + +When this service call is received, the node's life cycle state shall be shifted from the `Unconfigured` state to the `Configuring` state, and then from the `Configuring` state to the `Inactive` state or the `ErrorProcessing` state, according to the result of executing the function defined in the `Configuring` state. -These services may also be provided via attributes and method calls (for local management) in addition to being exposed ROS messages and topics/services (for remote management). -In the case of providing a ROS middleware interface, specific topics must be used, and they should be placed in a suitable namespace. +The service definition is: -Each possible supervisory transition will be provides as a service by the name of the transition except `create`. -`create` will require an extra argument for finding the node to instantiate. -The service will report whether the transition was successfully completed. + --- + uint8 result -### Lifecycle events +`result` shall be `SUCCESS` if the node's life cycle successfully moved to the `Inactive` state and the result of the `onConfigure()` function (executed by the `Configuring` state) was `success`. -A topic should be provided to broadcast the new life cycle state when it changes. -This topic must be latched. -The topic must be named `lifecycle_state` it will carry both the end state and the transition, with result code. -It will publish ever time that a transition is triggered, whether successful or not. +`result` shall be `TRANSITION_ERROR` if the result of the `onConfigure()` function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. -## Node Management +`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in the `Unconfigured` state when the request is received. -There are several different ways in which a managed node may transition between states. -Most state transitions are expected to be coordinated by an external management tool which will provide the node with it's configuration and start it. -The external management tool is also expected monitor it and execute recovery behaviors in case of failures. -A local management tool is also a possibility, leveraging method level interfaces. -And a node could be configured to self manage, however this is discouraged as this will interfere with external logic trying to managed the node via the interface. +### Cleanup transition request service -There is one transition expected to originate locally, which is the `ERROR` transition. +The service `infra/lifecycle/cleanup` service shall be provided by the life cycle interface. -A managed node may also want to expose arguments to automatically configure and activate when run in an unmanaged system. +When this service call is received, the node's life cycle state shall be shifted from the `Inactive` state to the `CleaningUp` state, and then from the `CleaningUp` state to the `Unconfigured` state or the `ErrorProcessing` state, according to the result of executing the function defined in the `CleaningUp`` state. + +The service definition is: + + --- + uint8 result + +`result` shall be `SUCCESS` if the node's life cycle successfully moved to the `Unconfigured` state and the result of the `onCleanup()` function (executed by the `CleaningUp` state) was `success`. + +`result` shall be `TRANSITION_ERROR` if the result of the `onCleanup()` function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. + +`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in the `Inactive` state when the request is received. + +### Activate transition request service + +The service `infra/lifecycle/activate` service shall be provided by the life cycle interface. + +When this service call is received, the node's life cycle state shall be shifted from the `Inactive` state to the `Activating` state, and then from the `Activating` state to the `Active` state or the `ErrorProcessing` state, according to the result of executing the function defined in the `Activating`` state. + +The service definition is: + + --- + uint8 result + +`result` shall be `SUCCESS` if the node's life cycle successfully moved to the `Active` state and the result of the `onActivate()` function (executed by the `Activating` state) was `success`. + +`result` shall be `TRANSITION_ERROR` if the result of the `onActivate()` function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. + +`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in the `Inactive` state when the request is received. + +### Deactivate transition request service + +The service `infra/lifecycle/deactivate` service shall be provided by the life cycle interface. + +When this service call is received, the node's life cycle state shall be shifted from the `Active` state to the `Deactivating` state, and then from the `Deactivating` state to the `Inactive` state or the `ErrorProcessing` state, according to the result of executing the function defined in the `Deactivating`` state. + +The service definition is: + + --- + uint8 result + +`result` shall be `SUCCESS` if the node's life cycle successfully moved to the `Inactive` state and the result of the `onDeactivate()` function (executed by the `Deactivating` state) was `success`. + +`result` shall be `TRANSITION_ERROR` if the result of the `onDeactivate()` function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. + +`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in the `Active` state when the request is received. + +### Shutdown transition request service + +The service `infra/lifecycle/shutdown` service shall be provided by the life cycle interface. + +When this service call is received, the node's life cycle state shall be shifted from the `Unconfigured` state, `Inactive` state or `Active` state to the `ShuttingDown` state, and then from the `ShuttingDown` state to the `Finalized` state or the `ErrorProcessing` state, according to the result of executing the function defined in the `ShuttingDown`` state. + +The service definition is: + + --- + uint8 result + +`result` shall be `SUCCESS` if the node's life cycle successfully moved to the `Finalized` state and the result of the `onShutdown()` function (executed by the `ShuttingDown` state) was `success`. + +`result` shall be `TRANSITION_ERROR` if the result of the `onShutdown()` function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. + +`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in one of the `Unconfigured`, `Inactive` or `Active` states when the request is received. + +### Provision of the interface + +What provides the interface is implementation dependent. +It may be provided directly by the node object itself, by a container object, or by any other means as appropriate to the technologies being used to implement the node and ROS infrastructure. + +It is expected that a common pattern will be to have a container class which loads a managed node implementation from a library and through a plugin architecture automatically exposes the required management interface via methods and the container is not subject to the lifecycle management. +However, it is fully valid to consider any implementation which provides this interface and follows the lifecycle policies a managed node. +Conversely, any object that provides these services but does not behave in the way defined in the life cycle state machine is malformed. ## Extensions From c0f964bf2ff6a1a2e1ba819b37993903f0757870 Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Wed, 9 Nov 2016 13:56:30 -0500 Subject: [PATCH 02/13] Combined transition control services into one --- articles/node_lifecycle.md | 112 +++++++++++-------------------------- 1 file changed, 32 insertions(+), 80 deletions(-) diff --git a/articles/node_lifecycle.md b/articles/node_lifecycle.md index 653182f0d..8ce6dd301 100644 --- a/articles/node_lifecycle.md +++ b/articles/node_lifecycle.md @@ -205,7 +205,7 @@ This transition should always succeed. ### Create Transition -This transition will instantiate the node, but will not run any code beyond the constructor. +This transition will instantiate the node, but will not run any code beyond the constructor.settings.settings. ## Management Interface @@ -243,14 +243,6 @@ The messages used by the interface shall use the following enumeration for indic uint8 DEACTIVATING=14 uint8 ERROR_PROCESSING=15 -### Transition result enumerations - -The messages used by the interface shall use the following enumeration for indicating the result of transitions. - - uint8 TRANSITION_ERROR=0 - uint8 SUCCESS=1 - uint8 WRONG_PREV_STATE=10 - ### Life cycle state changes topic When the node's life cycle changes, it shall broadcast the following message on the `infra/lifecycle/state_change` topic. @@ -259,9 +251,11 @@ When the node's life cycle changes, it shall broadcast the following message on uint8 next_state string trigger -`trigger` may be filled in containing a reason for the life cycle change. This value is optional. +`trigger` may be filled in containing a reason for the life cycle change. +This value is optional. -This topic must be latched. A history of a suitable length should be provided. +This topic must at a minimum make the most recent message available to new subscribers at all times. +This may be achieved by use of appropriate QoS settings. For example, if the `talker` node transitions from the `Active` state to the `Finalised` state via the `ShuttingDown` state in response to an external request to shut down the node, it will produce the following sequence of messages on this topic (values for `trigger` are illustrative only): @@ -313,90 +307,48 @@ The service definition is: The `UNKNOWN`/`unknown` value shall be assumed by clients of the service to indicate that the node is in an unknown state and thus unusable. -### Configure transition request service - -The service `infra/lifecycle/configure` service shall be provided by the life cycle interface. - -When this service call is received, the node's life cycle state shall be shifted from the `Unconfigured` state to the `Configuring` state, and then from the `Configuring` state to the `Inactive` state or the `ErrorProcessing` state, according to the result of executing the function defined in the `Configuring` state. - -The service definition is: - - --- - uint8 result - -`result` shall be `SUCCESS` if the node's life cycle successfully moved to the `Inactive` state and the result of the `onConfigure()` function (executed by the `Configuring` state) was `success`. - -`result` shall be `TRANSITION_ERROR` if the result of the `onConfigure()` function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. - -`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in the `Unconfigured` state when the request is received. - -### Cleanup transition request service - -The service `infra/lifecycle/cleanup` service shall be provided by the life cycle interface. - -When this service call is received, the node's life cycle state shall be shifted from the `Inactive` state to the `CleaningUp` state, and then from the `CleaningUp` state to the `Unconfigured` state or the `ErrorProcessing` state, according to the result of executing the function defined in the `CleaningUp`` state. - -The service definition is: - - --- - uint8 result - -`result` shall be `SUCCESS` if the node's life cycle successfully moved to the `Unconfigured` state and the result of the `onCleanup()` function (executed by the `CleaningUp` state) was `success`. - -`result` shall be `TRANSITION_ERROR` if the result of the `onCleanup()` function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. - -`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in the `Inactive` state when the request is received. +### Transition request service -### Activate transition request service +The service `infra/lifecycle/change_state` service shall be provided by the life cycle interface. -The service `infra/lifecycle/activate` service shall be provided by the life cycle interface. +When this service call is received, the node's life cycle state shall be shifted to the requested state via any appropriate intermediate states in accordance with the state diagram shown above. -When this service call is received, the node's life cycle state shall be shifted from the `Inactive` state to the `Activating` state, and then from the `Activating` state to the `Active` state or the `ErrorProcessing` state, according to the result of executing the function defined in the `Activating`` state. +For example, if the node is in the `Inactive` state and a request is made to shift to the `Active` state, the node's life cycle shall first be shifted to the `Activating` state. +Based on the result of the `onActivate()` function called during the `Activating` state, the node's life cycle shall then shift to either the `Active` state or the `ErrorProcessing` state. The service definition is: - --- - uint8 result - -`result` shall be `SUCCESS` if the node's life cycle successfully moved to the `Active` state and the result of the `onActivate()` function (executed by the `Activating` state) was `success`. - -`result` shall be `TRANSITION_ERROR` if the result of the `onActivate()` function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. - -`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in the `Inactive` state when the request is received. - -### Deactivate transition request service - -The service `infra/lifecycle/deactivate` service shall be provided by the life cycle interface. - -When this service call is received, the node's life cycle state shall be shifted from the `Active` state to the `Deactivating` state, and then from the `Deactivating` state to the `Inactive` state or the `ErrorProcessing` state, according to the result of executing the function defined in the `Deactivating`` state. + # Allowable transitions + uint8 CONFIGURE=0 + uint8 CLEANUP=1 + uint8 ACTIVATE=2 + uint8 DEACTIVATE=3 + uint8 SHUTDOWN=4 + # Transition results + uint8 TRANSITION_ERROR=0 + uint8 SUCCESS=1 + uint8 WRONG_PREV_STATE=10 -The service definition is: + uint8 transition --- uint8 result -`result` shall be `SUCCESS` if the node's life cycle successfully moved to the `Inactive` state and the result of the `onDeactivate()` function (executed by the `Deactivating` state) was `success`. - -`result` shall be `TRANSITION_ERROR` if the result of the `onDeactivate()` function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. - -`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in the `Active` state when the request is received. - -### Shutdown transition request service +`transition` must take one of the values defined in the transitions enumeration. +Additionally, the allowable values for `transition` is determined by the current life cycle state. +`transition` must take one of the following values, depending on the current life cycle state. -The service `infra/lifecycle/shutdown` service shall be provided by the life cycle interface. - -When this service call is received, the node's life cycle state shall be shifted from the `Unconfigured` state, `Inactive` state or `Active` state to the `ShuttingDown` state, and then from the `ShuttingDown` state to the `Finalized` state or the `ErrorProcessing` state, according to the result of executing the function defined in the `ShuttingDown`` state. - -The service definition is: - - --- - uint8 result + Current state | `transition` allowable values + Unconfigured | `CONFIGURE`, `SHUTDOWN` + Inactive | `ACTIVATE`, `CLEANUP`, `SHUTDOWN` + Active | `DEACTIVATE`, `SHUTDOWN` + Finalized | None -`result` shall be `SUCCESS` if the node's life cycle successfully moved to the `Finalized` state and the result of the `onShutdown()` function (executed by the `ShuttingDown` state) was `success`. +`result` shall be `SUCCESS` if the node's life cycle successfully moved to the requested state and the results of any intermediate state functions were all `success`. -`result` shall be `TRANSITION_ERROR` if the result of the `onShutdown()` function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. +`result` shall be `TRANSITION_ERROR` if the result of any intermediate state function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. -`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in one of the `Unconfigured`, `Inactive` or `Active` states when the request is received. +`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in the correct predecessor state for the requested transition, as described above. ### Provision of the interface From db9b3a823edd9f5c079f8abede35e0090a1b596b Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Fri, 11 Nov 2016 09:23:15 -0500 Subject: [PATCH 03/13] Clarify that create and destroy are container functionality --- articles/node_lifecycle.md | 23 +++++++++++++++++------ 1 file changed, 17 insertions(+), 6 deletions(-) diff --git a/articles/node_lifecycle.md b/articles/node_lifecycle.md index 8ce6dd301..379e7603e 100644 --- a/articles/node_lifecycle.md +++ b/articles/node_lifecycle.md @@ -53,14 +53,17 @@ There are also 6 transition states which are intermediate states during a reques In the transitions states logic will be executed to determine if the transition is successful. Success or failure shall be communicated to lifecycle management software through the lifecycle management interface. -There are 7 transitions exposed to a supervisory process, they are: +There are 5 transitions exposed to a supervisory process, they are: -- `create` - `configure` - `cleanup` - `activate` - `deactive` - `shutdown` + +Additionally, there are two transitions that may be exposed by a supervisory process if dynamic creation and destruction of nodes is supported by that supervisory process. + +- `create` - `destroy` The behavior of each state is as defined below. @@ -196,6 +199,18 @@ Transitions to `ErrorProcessing` may be caused by error return codes in callback - If the `onShutdown` callback raises or results in any other result code the node will transition to `Finalized`. +## Use of a supervisory process + +Managed nodes may be instantiated manually by a developer. +In this case, the developer's own code is responsible for creating and destroying the node. +However, the node may alternatively be owned by a container system. +The container will be responsible for creating and destroying the node. +Such a container will be responsible for exposing the following two transitions. + +### Create Transition + +This transition will instantiate the node, but will not run any code beyond the constructor. + ### Destroy Transition This transition will simply cause the deallocation of the node. @@ -203,10 +218,6 @@ In an object oriented environment it may just involve invoking the destructor. Otherwise it will invoke a standard deallocation method. This transition should always succeed. -### Create Transition - -This transition will instantiate the node, but will not run any code beyond the constructor.settings.settings. - ## Management Interface A node that has a managed life cycle complying with the above life cycle shall provide the following interface via ROS topics and services. From 6a96db1c6c19621c7b9038f8bd35ab99796b94fa Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Mon, 17 Apr 2017 15:40:27 +0900 Subject: [PATCH 04/13] Add link to message definition file for state enum --- articles/node_lifecycle.md | 30 +++++++++++++++++++----------- 1 file changed, 19 insertions(+), 11 deletions(-) diff --git a/articles/node_lifecycle.md b/articles/node_lifecycle.md index 379e7603e..d06cc0ec8 100644 --- a/articles/node_lifecycle.md +++ b/articles/node_lifecycle.md @@ -242,17 +242,25 @@ In other words, tooling shall judge if a node is managed or not by the presence The messages used by the interface shall use the following enumeration for indicating states. - uint8 UNKNOWN=0 - uint8 UNCONFIGURED=1 - uint8 INACTIVE=2 - uint8 ACTIVE=3 - uint8 FINALIZED=4 - uint8 CONFIGURING=10 - uint8 CLEANING_UP=11 - uint8 SHUTTING_DOWN=12 - uint8 ACTIVATING=13 - uint8 DEACTIVATING=14 - uint8 ERROR_PROCESSING=15 + # Primary states + uint8 PRIMARY_STATE_UNKNOWN = 0 + uint8 PRIMARY_STATE_UNCONFIGURED = 1 + uint8 PRIMARY_STATE_INACTIVE = 2 + uint8 PRIMARY_STATE_ACTIVE = 3 + uint8 PRIMARY_STATE_FINALIZED = 4 + + # Temporary intermediate states + uint8 TRANSITION_STATE_CONFIGURING = 10 + uint8 TRANSITION_STATE_CLEANINGUP = 11 + uint8 TRANSITION_STATE_SHUTTINGDOWN = 12 + uint8 TRANSITION_STATE_ACTIVATING = 13 + uint8 TRANSITION_STATE_DEACTIVATING = 14 + uint8 TRANSITION_STATE_ERRORPROCESSING = 15 + + uint8 id + string label + +See for example the [message definition used by `RCL`](https://raw.githubusercontent.com/ros2/rcl_interfaces/master/lifecycle_msgs/msg/State.msg). ### Life cycle state changes topic From f7edec904650fb2be2923fa294afafa5135d43fd Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Mon, 17 Apr 2017 16:13:07 +0900 Subject: [PATCH 05/13] Make the infra namespace hidden --- articles/node_lifecycle.md | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/articles/node_lifecycle.md b/articles/node_lifecycle.md index d06cc0ec8..fd5ec28d7 100644 --- a/articles/node_lifecycle.md +++ b/articles/node_lifecycle.md @@ -228,15 +228,15 @@ They shall not be disabled by the node shifting to the `Inactive` state, for exa ### Interface namespace -The interface shall be provided in a namespace named "infra/lifecycle" underneath the node's namespace. +The interface shall be provided in a namespace named "_infra/lifecycle" underneath the node's namespace. -For example, if a node named `talker` has a managed life cycle complying with the state machine described above, it shall provide topics under the namespace `/talker/infra/lifecycle`. +For example, if a node named `talker` has a managed life cycle complying with the state machine described above, it shall provide topics under the namespace `/talker/_infra/lifecycle`. All examples in the following sections are also given assuming a node named `talker`. -If the `infra/lifecycle` namespace is available under a node's namespace, then that node shall be assumed to be functioning according to the managed life cycle. -If the node is not functioning according to the managed life cycle, the `infra/lifecycle` namespace shall not exist. -In other words, tooling shall judge if a node is managed or not by the presence of the `infra/lifecycle` namespace. +If the `_infra/lifecycle` namespace is available under a node's namespace, then that node shall be assumed to be functioning according to the managed life cycle. +If the node is not functioning according to the managed life cycle, the `_infra/lifecycle` namespace shall not exist. +In other words, tooling shall judge if a node is managed or not by the presence of the `_infra/lifecycle` namespace. ### State enumerations @@ -264,7 +264,7 @@ See for example the [message definition used by `RCL`](https://raw.githubusercon ### Life cycle state changes topic -When the node's life cycle changes, it shall broadcast the following message on the `infra/lifecycle/state_change` topic. +When the node's life cycle changes, it shall broadcast the following message on the `_infra/lifecycle/state_change` topic. uint8 previous_state uint8 next_state @@ -302,7 +302,7 @@ If the `talker` node transitions from the `Inactive` state to the `Unconfigured` ### Current life cycle state service -The node's current life cycle state shall be available via the `infra/lifecycle/get_state` service. +The node's current life cycle state shall be available via the `_infra/lifecycle/get_state` service. The service definition is: --- @@ -328,7 +328,7 @@ The `UNKNOWN`/`unknown` value shall be assumed by clients of the service to indi ### Transition request service -The service `infra/lifecycle/change_state` service shall be provided by the life cycle interface. +The service `_infra/lifecycle/change_state` service shall be provided by the life cycle interface. When this service call is received, the node's life cycle state shall be shifted to the requested state via any appropriate intermediate states in accordance with the state diagram shown above. From 7a7a72d3949a648858aaf7b5ead8b402a1d51450 Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Wed, 6 Sep 2017 10:38:31 +0900 Subject: [PATCH 06/13] Start of article about actions --- articles/051_actions.md | 146 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 146 insertions(+) create mode 100644 articles/051_actions.md diff --git a/articles/051_actions.md b/articles/051_actions.md new file mode 100644 index 000000000..de8f5462e --- /dev/null +++ b/articles/051_actions.md @@ -0,0 +1,146 @@ +--- +layout: default +title: Actions +permalink: articles/actions.html +abstract: + Despite their implementation as a separate library and lack of a detailed specification, actions are one of the three core types of interaction between ROS nodes. Their asynchronous nature combined with the feedback and control mechanism gives them significantly more power than a standard RPC. This article formalises the requirements for actions, including what a ROS user should see and what the middleware layer should provide. +author: '[Geoffrey Biggs](https://github.com/gbiggs)' +published: true +--- + +{:toc} + +# {{ page.title }} + +
+{{ page.abstract }} +
+ +Original Author: {{ page.author }} + +## Background + +ROS services, which provide synchronous Remote Procedure Calls, are a useful +concept for sending a request and getting a rapid reply. But in robotics there +are many instances where a reply may take a significant length of time. +Additionally, there are occasions when it is useful to send a request to +do some processing or perform some action in the world, where the result is +less important than the effect of carrying it out. The progress of such +requests often needs to be tracked, success or failure must be known in +addition to receiving back information produced, and the request may need to be +cancelled or altered before it completes. These requirements cannot be +fulfilled by a simple RPC mechanism, whether or not it is asynchronous. + +To satisfy these use cases, ROS provides a third communication paradigm known +as "actions". An action is a goal-oriented request that occurs asynchronously +to the requester, is typically (but not necessarily) longer-running than +immediate, can be cancelled or replaced during execution, and has a server that +provides feedback on execution progress. + +This document defines how actions are specified, what they look like to ROS +users (both node developers and system integrators) + +## Action specification + +Actions are specified using a form of the ROS Message IDL. The specification +contains three sections, each of which is a message specification: + +1. Goal + +1. Result + +1. Feedback + +Any of these sections may be empty. + +Between the three sections is a line containing three hyphens, `---`. + +Action specifications are stored in a file ending in `.action`. There is one +action specification per `.action` file. + +An example action specification [taken from the actionlib wiki] is shown below. + +``` +# Define the goal +uint32 dishwasher_id # Specify which dishwasher we want to use +--- +# Define the result +uint32 total_dishes_cleaned +--- +# Define a feedback message +float32 percent_complete +uint32 number_dishes_cleaned +``` + +## Serving and using actions + +Actions are a first-class citizen in the ROS API, alongside topics and +services. + +Action clients will use an API that provides a proxy object for the action. +This will be a templated class, using the action class generated from the +action specification as the template parameter. The client shall create an +instance of this class, providing the address of the intended action server. +Each instance of this class can only be related to one action server. Methods +of the class will provide facilities for sending a goal to the action server, +receiving a result, and getting feedback. + +Action servers will use an API that provides a templated server class, using +the action class generated from the action specification as the template +parameter. The node implementer will create a function that implements the +action's behaviour, create an instance of the templated server class, and bind +the implementing function to the server. The implementing function will receive +as one of its parameters the received goal message, and as another parameter +the action server instance. The implementation shall use the action server +instance to provide progress feedback and to report the result and +success/failure/error status of the action's execution. + +Actions may be used from or served by real-time nodes. Therefore the actions +API must be real-time capable. + +## Introspection tools + +Actions, like topics and services, are introspectable from the command line. + +In ROS 1, actions are visible in the output of the `rostopic` tool. + +In ROS 2, actions will not be visible as a set of topics. Nor will they be +visible as a set of services [in the case that services be used to implement +them]. They will be visible using a separate `ros2 action` command line tool. + +The command line tool will be similar to the `ros2 service` tool. It will be +able to: + +- list known actions, +- display the arguments for an action's goal, +- display the type of an action's feedback and result, +- display information about the server of an action, +- display the underlying topics and/or services providing the action, +- find actions by action type, and +- call an action, display feedback as it is received, display the result when + received, and cancel the action (when the tool is terminated prematurely) + +Each action, despite using multiple topics and/or services in its +implementation, will be listed and treated as a single unit by this tool. [This +will probably be a namespace that contains the underlying topics, etc.] + +## Middleware implementation + +In ROS 1, actions are implemented using a set of topics under a namespace taken +from the action name. This implementation was chosen because ROS services are +inherently synchronous, and so incompatible with the asynchronous nature of the +action concept. There is also a need for a status/feedback channel and a +control channel. + +The Remote Procedure Call over DDS (DDS-RPC) specification does not explicitly +provide facilities for interrupting service calls or receiving feedback on +their progress. It does provide for receiving both a return value from a +request and, at the same time, an indication of whether the request was +successful or raised an exception, with the exception type included in this +information. + +This means that an implementation of actions cannot simply be a DDS-style RPC. +The implementation must separately provide status/feedback and control +channels. While a control channel could be implemented as a separate RPC, due +to the dataflow nature of feedback it would be best implemented as a separate +topic. From 1ef7e71d257a13257d712a52a27aef1cd20498d5 Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Wed, 6 Sep 2017 10:40:24 +0900 Subject: [PATCH 07/13] Unwrap --- articles/051_actions.md | 97 ++++++++++------------------------------- 1 file changed, 23 insertions(+), 74 deletions(-) diff --git a/articles/051_actions.md b/articles/051_actions.md index de8f5462e..f93d6c8d6 100644 --- a/articles/051_actions.md +++ b/articles/051_actions.md @@ -20,30 +20,15 @@ Original Author: {{ page.author }} ## Background -ROS services, which provide synchronous Remote Procedure Calls, are a useful -concept for sending a request and getting a rapid reply. But in robotics there -are many instances where a reply may take a significant length of time. -Additionally, there are occasions when it is useful to send a request to -do some processing or perform some action in the world, where the result is -less important than the effect of carrying it out. The progress of such -requests often needs to be tracked, success or failure must be known in -addition to receiving back information produced, and the request may need to be -cancelled or altered before it completes. These requirements cannot be -fulfilled by a simple RPC mechanism, whether or not it is asynchronous. - -To satisfy these use cases, ROS provides a third communication paradigm known -as "actions". An action is a goal-oriented request that occurs asynchronously -to the requester, is typically (but not necessarily) longer-running than -immediate, can be cancelled or replaced during execution, and has a server that -provides feedback on execution progress. - -This document defines how actions are specified, what they look like to ROS -users (both node developers and system integrators) +ROS services, which provide synchronous Remote Procedure Calls, are a useful concept for sending a request and getting a rapid reply. But in robotics there are many instances where a reply may take a significant length of time. Additionally, there are occasions when it is useful to send a request to do some processing or perform some action in the world, where the result is less important than the effect of carrying it out. The progress of such requests often needs to be tracked, success or failure must be known in addition to receiving back information produced, and the request may need to be cancelled or altered before it completes. These requirements cannot be fulfilled by a simple RPC mechanism, whether or not it is asynchronous. + +To satisfy these use cases, ROS provides a third communication paradigm known as "actions". An action is a goal-oriented request that occurs asynchronously to the requester, is typically (but not necessarily) longer-running than immediate, can be cancelled or replaced during execution, and has a server that provides feedback on execution progress. + +This document defines how actions are specified, what they look like to ROS users (both node developers and system integrators) ## Action specification -Actions are specified using a form of the ROS Message IDL. The specification -contains three sections, each of which is a message specification: +Actions are specified using a form of the ROS Message IDL. The specification contains three sections, each of which is a message specification: 1. Goal @@ -55,8 +40,7 @@ Any of these sections may be empty. Between the three sections is a line containing three hyphens, `---`. -Action specifications are stored in a file ending in `.action`. There is one -action specification per `.action` file. +Action specifications are stored in a file ending in `.action`. There is one action specification per `.action` file. An example action specification [taken from the actionlib wiki] is shown below. @@ -74,29 +58,13 @@ uint32 number_dishes_cleaned ## Serving and using actions -Actions are a first-class citizen in the ROS API, alongside topics and -services. - -Action clients will use an API that provides a proxy object for the action. -This will be a templated class, using the action class generated from the -action specification as the template parameter. The client shall create an -instance of this class, providing the address of the intended action server. -Each instance of this class can only be related to one action server. Methods -of the class will provide facilities for sending a goal to the action server, -receiving a result, and getting feedback. - -Action servers will use an API that provides a templated server class, using -the action class generated from the action specification as the template -parameter. The node implementer will create a function that implements the -action's behaviour, create an instance of the templated server class, and bind -the implementing function to the server. The implementing function will receive -as one of its parameters the received goal message, and as another parameter -the action server instance. The implementation shall use the action server -instance to provide progress feedback and to report the result and -success/failure/error status of the action's execution. - -Actions may be used from or served by real-time nodes. Therefore the actions -API must be real-time capable. +Actions are a first-class citizen in the ROS API, alongside topics and services. + +Action clients will use an API that provides a proxy object for the action. This will be a templated class, using the action class generated from the action specification as the template parameter. The client shall create an instance of this class, providing the address of the intended action server. Each instance of this class can only be related to one action server. Methods of the class will provide facilities for sending a goal to the action server, receiving a result, and getting feedback. + +Action servers will use an API that provides a templated server class, using the action class generated from the action specification as the template parameter. The node implementer will create a function that implements the action's behaviour, create an instance of the templated server class, and bind the implementing function to the server. The implementing function will receive as one of its parameters the received goal message, and as another parameter the action server instance. The implementation shall use the action server instance to provide progress feedback and to report the result and success/failure/error status of the action's execution. + +Actions may be used from or served by real-time nodes. Therefore the actions API must be real-time capable. ## Introspection tools @@ -104,12 +72,9 @@ Actions, like topics and services, are introspectable from the command line. In ROS 1, actions are visible in the output of the `rostopic` tool. -In ROS 2, actions will not be visible as a set of topics. Nor will they be -visible as a set of services [in the case that services be used to implement -them]. They will be visible using a separate `ros2 action` command line tool. +In ROS 2, actions will not be visible as a set of topics. Nor will they be visible as a set of services [in the case that services be used to implement them]. They will be visible using a separate `ros2 action` command line tool. -The command line tool will be similar to the `ros2 service` tool. It will be -able to: +The command line tool will be similar to the `ros2 service` tool. It will be able to: - list known actions, - display the arguments for an action's goal, @@ -117,30 +82,14 @@ able to: - display information about the server of an action, - display the underlying topics and/or services providing the action, - find actions by action type, and -- call an action, display feedback as it is received, display the result when - received, and cancel the action (when the tool is terminated prematurely) +- call an action, display feedback as it is received, display the result when received, and cancel the action (when the tool is terminated prematurely) -Each action, despite using multiple topics and/or services in its -implementation, will be listed and treated as a single unit by this tool. [This -will probably be a namespace that contains the underlying topics, etc.] +Each action, despite using multiple topics and/or services in its implementation, will be listed and treated as a single unit by this tool. [This will probably be a namespace that contains the underlying topics, etc.] ## Middleware implementation -In ROS 1, actions are implemented using a set of topics under a namespace taken -from the action name. This implementation was chosen because ROS services are -inherently synchronous, and so incompatible with the asynchronous nature of the -action concept. There is also a need for a status/feedback channel and a -control channel. - -The Remote Procedure Call over DDS (DDS-RPC) specification does not explicitly -provide facilities for interrupting service calls or receiving feedback on -their progress. It does provide for receiving both a return value from a -request and, at the same time, an indication of whether the request was -successful or raised an exception, with the exception type included in this -information. - -This means that an implementation of actions cannot simply be a DDS-style RPC. -The implementation must separately provide status/feedback and control -channels. While a control channel could be implemented as a separate RPC, due -to the dataflow nature of feedback it would be best implemented as a separate -topic. +In ROS 1, actions are implemented using a set of topics under a namespace taken from the action name. This implementation was chosen because ROS services are inherently synchronous, and so incompatible with the asynchronous nature of the action concept. There is also a need for a status/feedback channel and a control channel. + +The Remote Procedure Call over DDS (DDS-RPC) specification does not explicitly provide facilities for interrupting service calls or receiving feedback on their progress. It does provide for receiving both a return value from a request and, at the same time, an indication of whether the request was successful or raised an exception, with the exception type included in this information. + +This means that an implementation of actions cannot simply be a DDS-style RPC. The implementation must separately provide status/feedback and control channels. While a control channel could be implemented as a separate RPC, due to the dataflow nature of feedback it would be best implemented as a separate topic. From 391764a284de38b006ea3ed44e710694b142fc07 Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Wed, 6 Sep 2017 10:46:27 +0900 Subject: [PATCH 08/13] Shift over to upstream's version of node_lifecycle.md --- articles/node_lifecycle.md | 192 ++++++------------------------------- 1 file changed, 28 insertions(+), 164 deletions(-) diff --git a/articles/node_lifecycle.md b/articles/node_lifecycle.md index fd5ec28d7..d6e0715f6 100644 --- a/articles/node_lifecycle.md +++ b/articles/node_lifecycle.md @@ -53,17 +53,14 @@ There are also 6 transition states which are intermediate states during a reques In the transitions states logic will be executed to determine if the transition is successful. Success or failure shall be communicated to lifecycle management software through the lifecycle management interface. -There are 5 transitions exposed to a supervisory process, they are: +There are 7 transitions exposed to a supervisory process, they are: +- `create` - `configure` - `cleanup` - `activate` - `deactive` - `shutdown` - -Additionally, there are two transitions that may be exposed by a supervisory process if dynamic creation and destruction of nodes is supported by that supervisory process. - -- `create` - `destroy` The behavior of each state is as defined below. @@ -199,18 +196,6 @@ Transitions to `ErrorProcessing` may be caused by error return codes in callback - If the `onShutdown` callback raises or results in any other result code the node will transition to `Finalized`. -## Use of a supervisory process - -Managed nodes may be instantiated manually by a developer. -In this case, the developer's own code is responsible for creating and destroying the node. -However, the node may alternatively be owned by a container system. -The container will be responsible for creating and destroying the node. -Such a container will be responsible for exposing the following two transitions. - -### Create Transition - -This transition will instantiate the node, but will not run any code beyond the constructor. - ### Destroy Transition This transition will simply cause the deallocation of the node. @@ -218,165 +203,44 @@ In an object oriented environment it may just involve invoking the destructor. Otherwise it will invoke a standard deallocation method. This transition should always succeed. -## Management Interface - -A node that has a managed life cycle complying with the above life cycle shall provide the following interface via ROS topics and services. -This interface is to be used by tools to manage the node's life cycle state transitions, either automatically or manually according to the tool's purpose. - -The topics and services of this interface shall function in all states of the node's life cycle. -They shall not be disabled by the node shifting to the `Inactive` state, for example. - -### Interface namespace - -The interface shall be provided in a namespace named "_infra/lifecycle" underneath the node's namespace. - -For example, if a node named `talker` has a managed life cycle complying with the state machine described above, it shall provide topics under the namespace `/talker/_infra/lifecycle`. - -All examples in the following sections are also given assuming a node named `talker`. - -If the `_infra/lifecycle` namespace is available under a node's namespace, then that node shall be assumed to be functioning according to the managed life cycle. -If the node is not functioning according to the managed life cycle, the `_infra/lifecycle` namespace shall not exist. -In other words, tooling shall judge if a node is managed or not by the presence of the `_infra/lifecycle` namespace. - -### State enumerations - -The messages used by the interface shall use the following enumeration for indicating states. - - # Primary states - uint8 PRIMARY_STATE_UNKNOWN = 0 - uint8 PRIMARY_STATE_UNCONFIGURED = 1 - uint8 PRIMARY_STATE_INACTIVE = 2 - uint8 PRIMARY_STATE_ACTIVE = 3 - uint8 PRIMARY_STATE_FINALIZED = 4 - - # Temporary intermediate states - uint8 TRANSITION_STATE_CONFIGURING = 10 - uint8 TRANSITION_STATE_CLEANINGUP = 11 - uint8 TRANSITION_STATE_SHUTTINGDOWN = 12 - uint8 TRANSITION_STATE_ACTIVATING = 13 - uint8 TRANSITION_STATE_DEACTIVATING = 14 - uint8 TRANSITION_STATE_ERRORPROCESSING = 15 - - uint8 id - string label - -See for example the [message definition used by `RCL`](https://raw.githubusercontent.com/ros2/rcl_interfaces/master/lifecycle_msgs/msg/State.msg). - -### Life cycle state changes topic - -When the node's life cycle changes, it shall broadcast the following message on the `_infra/lifecycle/state_change` topic. - - uint8 previous_state - uint8 next_state - string trigger - -`trigger` may be filled in containing a reason for the life cycle change. -This value is optional. - -This topic must at a minimum make the most recent message available to new subscribers at all times. -This may be achieved by use of appropriate QoS settings. - -For example, if the `talker` node transitions from the `Active` state to the `Finalised` state via the `ShuttingDown` state in response to an external request to shut down the node, it will produce the following sequence of messages on this topic (values for `trigger` are illustrative only): - - previous_state = INACTIVE - next_state = SHUTTTING_DOWN - trigger = "shutdown request" - - previous_state = SHUTTING_DOWN - next_state = FINALIZED - trigger = "shutdown returned OK" - -If the `talker` node transitions from the `Inactive` state to the `Unconfigured` state via a request to activate the node and an error occurring in activation processing, it will produce the following sequence of messages: - - previous_state = INACTIVE - next_state = ACTIVATING - trigger = "activate request" - - previous_state = ACTIVATING - next_state = ERROR_PROCESSING - trigger = "error in activating state" - - previous_state = ERROR_PROCESSING - next_state = UNCONFIGURED - trigger = "error processing returned OK" - -### Current life cycle state service - -The node's current life cycle state shall be available via the `_infra/lifecycle/get_state` service. -The service definition is: - - --- - uint8 state - string state_name - -`state_name` must assume one of the following values, according to the value of `state`. - - Value of state | Value of state_name - UNKNOWN | unknown - UNCONFIGURED | unconfigured - INACTIVE | inactive - ACTIVE | active - FINALIZED | finalized - CONFIGURING | configuring - CLEANING_UP | cleaning_up - SHUTTING_DOWN | shutting_down - ACTIVATING | activating - DEACTIVATING | deactivating - ERROR_PROCESSING | error_processing - -The `UNKNOWN`/`unknown` value shall be assumed by clients of the service to indicate that the node is in an unknown state and thus unusable. - -### Transition request service - -The service `_infra/lifecycle/change_state` service shall be provided by the life cycle interface. - -When this service call is received, the node's life cycle state shall be shifted to the requested state via any appropriate intermediate states in accordance with the state diagram shown above. - -For example, if the node is in the `Inactive` state and a request is made to shift to the `Active` state, the node's life cycle shall first be shifted to the `Activating` state. -Based on the result of the `onActivate()` function called during the `Activating` state, the node's life cycle shall then shift to either the `Active` state or the `ErrorProcessing` state. +### Create Transition -The service definition is: +This transition will instantiate the node, but will not run any code beyond the constructor. - # Allowable transitions - uint8 CONFIGURE=0 - uint8 CLEANUP=1 - uint8 ACTIVATE=2 - uint8 DEACTIVATE=3 - uint8 SHUTDOWN=4 - # Transition results - uint8 TRANSITION_ERROR=0 - uint8 SUCCESS=1 - uint8 WRONG_PREV_STATE=10 +## Management Interface +A managed node will be exposed to the ROS ecosystem by the following interface, as seen by tools that perform the managing. +This interface should not be subject to the restrictions on communications imposed by the lifecycle states. - uint8 transition - --- - uint8 result +It is expected that a common pattern will be to have a container class which loads a managed node implementation from a library and through a plugin architecture automatically exposes the required management interface via methods and the container is not subject to the lifecycle management. +However, it is fully valid to consider any implementation which provides this interface and follows the lifecycle policies a managed node. +Conversely, any object that provides these services but does not behave in the way defined in the life cycle state machine is malformed. -`transition` must take one of the values defined in the transitions enumeration. -Additionally, the allowable values for `transition` is determined by the current life cycle state. -`transition` must take one of the following values, depending on the current life cycle state. +These services may also be provided via attributes and method calls (for local management) in addition to being exposed ROS messages and topics/services (for remote management). +In the case of providing a ROS middleware interface, specific topics must be used, and they should be placed in a suitable namespace. - Current state | `transition` allowable values - Unconfigured | `CONFIGURE`, `SHUTDOWN` - Inactive | `ACTIVATE`, `CLEANUP`, `SHUTDOWN` - Active | `DEACTIVATE`, `SHUTDOWN` - Finalized | None +Each possible supervisory transition will be provides as a service by the name of the transition except `create`. +`create` will require an extra argument for finding the node to instantiate. +The service will report whether the transition was successfully completed. -`result` shall be `SUCCESS` if the node's life cycle successfully moved to the requested state and the results of any intermediate state functions were all `success`. +### Lifecycle events -`result` shall be `TRANSITION_ERROR` if the result of any intermediate state function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. +A topic should be provided to broadcast the new life cycle state when it changes. +This topic must be latched. +The topic must be named `lifecycle_state` it will carry both the end state and the transition, with result code. +It will publish ever time that a transition is triggered, whether successful or not. -`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in the correct predecessor state for the requested transition, as described above. +## Node Management -### Provision of the interface +There are several different ways in which a managed node may transition between states. +Most state transitions are expected to be coordinated by an external management tool which will provide the node with it's configuration and start it. +The external management tool is also expected monitor it and execute recovery behaviors in case of failures. +A local management tool is also a possibility, leveraging method level interfaces. +And a node could be configured to self manage, however this is discouraged as this will interfere with external logic trying to managed the node via the interface. -What provides the interface is implementation dependent. -It may be provided directly by the node object itself, by a container object, or by any other means as appropriate to the technologies being used to implement the node and ROS infrastructure. +There is one transition expected to originate locally, which is the `ERROR` transition. -It is expected that a common pattern will be to have a container class which loads a managed node implementation from a library and through a plugin architecture automatically exposes the required management interface via methods and the container is not subject to the lifecycle management. -However, it is fully valid to consider any implementation which provides this interface and follows the lifecycle policies a managed node. -Conversely, any object that provides these services but does not behave in the way defined in the life cycle state machine is malformed. +A managed node may also want to expose arguments to automatically configure and activate when run in an unmanaged system. ## Extensions From c1afa2dcfd1f602a6eaf06b59efceee9e34d6fb5 Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Wed, 6 Sep 2017 10:52:55 +0900 Subject: [PATCH 09/13] Revert "Shift over to upstream's version of node_lifecycle.md" This reverts commit 391764a284de38b006ea3ed44e710694b142fc07. --- articles/node_lifecycle.md | 192 +++++++++++++++++++++++++++++++------ 1 file changed, 164 insertions(+), 28 deletions(-) diff --git a/articles/node_lifecycle.md b/articles/node_lifecycle.md index d6e0715f6..fd5ec28d7 100644 --- a/articles/node_lifecycle.md +++ b/articles/node_lifecycle.md @@ -53,14 +53,17 @@ There are also 6 transition states which are intermediate states during a reques In the transitions states logic will be executed to determine if the transition is successful. Success or failure shall be communicated to lifecycle management software through the lifecycle management interface. -There are 7 transitions exposed to a supervisory process, they are: +There are 5 transitions exposed to a supervisory process, they are: -- `create` - `configure` - `cleanup` - `activate` - `deactive` - `shutdown` + +Additionally, there are two transitions that may be exposed by a supervisory process if dynamic creation and destruction of nodes is supported by that supervisory process. + +- `create` - `destroy` The behavior of each state is as defined below. @@ -196,6 +199,18 @@ Transitions to `ErrorProcessing` may be caused by error return codes in callback - If the `onShutdown` callback raises or results in any other result code the node will transition to `Finalized`. +## Use of a supervisory process + +Managed nodes may be instantiated manually by a developer. +In this case, the developer's own code is responsible for creating and destroying the node. +However, the node may alternatively be owned by a container system. +The container will be responsible for creating and destroying the node. +Such a container will be responsible for exposing the following two transitions. + +### Create Transition + +This transition will instantiate the node, but will not run any code beyond the constructor. + ### Destroy Transition This transition will simply cause the deallocation of the node. @@ -203,44 +218,165 @@ In an object oriented environment it may just involve invoking the destructor. Otherwise it will invoke a standard deallocation method. This transition should always succeed. -### Create Transition +## Management Interface -This transition will instantiate the node, but will not run any code beyond the constructor. +A node that has a managed life cycle complying with the above life cycle shall provide the following interface via ROS topics and services. +This interface is to be used by tools to manage the node's life cycle state transitions, either automatically or manually according to the tool's purpose. -## Management Interface +The topics and services of this interface shall function in all states of the node's life cycle. +They shall not be disabled by the node shifting to the `Inactive` state, for example. -A managed node will be exposed to the ROS ecosystem by the following interface, as seen by tools that perform the managing. -This interface should not be subject to the restrictions on communications imposed by the lifecycle states. +### Interface namespace -It is expected that a common pattern will be to have a container class which loads a managed node implementation from a library and through a plugin architecture automatically exposes the required management interface via methods and the container is not subject to the lifecycle management. -However, it is fully valid to consider any implementation which provides this interface and follows the lifecycle policies a managed node. -Conversely, any object that provides these services but does not behave in the way defined in the life cycle state machine is malformed. +The interface shall be provided in a namespace named "_infra/lifecycle" underneath the node's namespace. + +For example, if a node named `talker` has a managed life cycle complying with the state machine described above, it shall provide topics under the namespace `/talker/_infra/lifecycle`. + +All examples in the following sections are also given assuming a node named `talker`. + +If the `_infra/lifecycle` namespace is available under a node's namespace, then that node shall be assumed to be functioning according to the managed life cycle. +If the node is not functioning according to the managed life cycle, the `_infra/lifecycle` namespace shall not exist. +In other words, tooling shall judge if a node is managed or not by the presence of the `_infra/lifecycle` namespace. + +### State enumerations + +The messages used by the interface shall use the following enumeration for indicating states. + + # Primary states + uint8 PRIMARY_STATE_UNKNOWN = 0 + uint8 PRIMARY_STATE_UNCONFIGURED = 1 + uint8 PRIMARY_STATE_INACTIVE = 2 + uint8 PRIMARY_STATE_ACTIVE = 3 + uint8 PRIMARY_STATE_FINALIZED = 4 + + # Temporary intermediate states + uint8 TRANSITION_STATE_CONFIGURING = 10 + uint8 TRANSITION_STATE_CLEANINGUP = 11 + uint8 TRANSITION_STATE_SHUTTINGDOWN = 12 + uint8 TRANSITION_STATE_ACTIVATING = 13 + uint8 TRANSITION_STATE_DEACTIVATING = 14 + uint8 TRANSITION_STATE_ERRORPROCESSING = 15 + + uint8 id + string label + +See for example the [message definition used by `RCL`](https://raw.githubusercontent.com/ros2/rcl_interfaces/master/lifecycle_msgs/msg/State.msg). + +### Life cycle state changes topic + +When the node's life cycle changes, it shall broadcast the following message on the `_infra/lifecycle/state_change` topic. -These services may also be provided via attributes and method calls (for local management) in addition to being exposed ROS messages and topics/services (for remote management). -In the case of providing a ROS middleware interface, specific topics must be used, and they should be placed in a suitable namespace. + uint8 previous_state + uint8 next_state + string trigger -Each possible supervisory transition will be provides as a service by the name of the transition except `create`. -`create` will require an extra argument for finding the node to instantiate. -The service will report whether the transition was successfully completed. +`trigger` may be filled in containing a reason for the life cycle change. +This value is optional. -### Lifecycle events +This topic must at a minimum make the most recent message available to new subscribers at all times. +This may be achieved by use of appropriate QoS settings. -A topic should be provided to broadcast the new life cycle state when it changes. -This topic must be latched. -The topic must be named `lifecycle_state` it will carry both the end state and the transition, with result code. -It will publish ever time that a transition is triggered, whether successful or not. +For example, if the `talker` node transitions from the `Active` state to the `Finalised` state via the `ShuttingDown` state in response to an external request to shut down the node, it will produce the following sequence of messages on this topic (values for `trigger` are illustrative only): -## Node Management + previous_state = INACTIVE + next_state = SHUTTTING_DOWN + trigger = "shutdown request" -There are several different ways in which a managed node may transition between states. -Most state transitions are expected to be coordinated by an external management tool which will provide the node with it's configuration and start it. -The external management tool is also expected monitor it and execute recovery behaviors in case of failures. -A local management tool is also a possibility, leveraging method level interfaces. -And a node could be configured to self manage, however this is discouraged as this will interfere with external logic trying to managed the node via the interface. + previous_state = SHUTTING_DOWN + next_state = FINALIZED + trigger = "shutdown returned OK" -There is one transition expected to originate locally, which is the `ERROR` transition. +If the `talker` node transitions from the `Inactive` state to the `Unconfigured` state via a request to activate the node and an error occurring in activation processing, it will produce the following sequence of messages: -A managed node may also want to expose arguments to automatically configure and activate when run in an unmanaged system. + previous_state = INACTIVE + next_state = ACTIVATING + trigger = "activate request" + + previous_state = ACTIVATING + next_state = ERROR_PROCESSING + trigger = "error in activating state" + + previous_state = ERROR_PROCESSING + next_state = UNCONFIGURED + trigger = "error processing returned OK" + +### Current life cycle state service + +The node's current life cycle state shall be available via the `_infra/lifecycle/get_state` service. +The service definition is: + + --- + uint8 state + string state_name + +`state_name` must assume one of the following values, according to the value of `state`. + + Value of state | Value of state_name + UNKNOWN | unknown + UNCONFIGURED | unconfigured + INACTIVE | inactive + ACTIVE | active + FINALIZED | finalized + CONFIGURING | configuring + CLEANING_UP | cleaning_up + SHUTTING_DOWN | shutting_down + ACTIVATING | activating + DEACTIVATING | deactivating + ERROR_PROCESSING | error_processing + +The `UNKNOWN`/`unknown` value shall be assumed by clients of the service to indicate that the node is in an unknown state and thus unusable. + +### Transition request service + +The service `_infra/lifecycle/change_state` service shall be provided by the life cycle interface. + +When this service call is received, the node's life cycle state shall be shifted to the requested state via any appropriate intermediate states in accordance with the state diagram shown above. + +For example, if the node is in the `Inactive` state and a request is made to shift to the `Active` state, the node's life cycle shall first be shifted to the `Activating` state. +Based on the result of the `onActivate()` function called during the `Activating` state, the node's life cycle shall then shift to either the `Active` state or the `ErrorProcessing` state. + +The service definition is: + + # Allowable transitions + uint8 CONFIGURE=0 + uint8 CLEANUP=1 + uint8 ACTIVATE=2 + uint8 DEACTIVATE=3 + uint8 SHUTDOWN=4 + # Transition results + uint8 TRANSITION_ERROR=0 + uint8 SUCCESS=1 + uint8 WRONG_PREV_STATE=10 + + + uint8 transition + --- + uint8 result + +`transition` must take one of the values defined in the transitions enumeration. +Additionally, the allowable values for `transition` is determined by the current life cycle state. +`transition` must take one of the following values, depending on the current life cycle state. + + Current state | `transition` allowable values + Unconfigured | `CONFIGURE`, `SHUTDOWN` + Inactive | `ACTIVATE`, `CLEANUP`, `SHUTDOWN` + Active | `DEACTIVATE`, `SHUTDOWN` + Finalized | None + +`result` shall be `SUCCESS` if the node's life cycle successfully moved to the requested state and the results of any intermediate state functions were all `success`. + +`result` shall be `TRANSITION_ERROR` if the result of any intermediate state function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. + +`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in the correct predecessor state for the requested transition, as described above. + +### Provision of the interface + +What provides the interface is implementation dependent. +It may be provided directly by the node object itself, by a container object, or by any other means as appropriate to the technologies being used to implement the node and ROS infrastructure. + +It is expected that a common pattern will be to have a container class which loads a managed node implementation from a library and through a plugin architecture automatically exposes the required management interface via methods and the container is not subject to the lifecycle management. +However, it is fully valid to consider any implementation which provides this interface and follows the lifecycle policies a managed node. +Conversely, any object that provides these services but does not behave in the way defined in the life cycle state machine is malformed. ## Extensions From a8cee359676452bed3cbf85ed143ab9a0f753d5c Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Wed, 6 Sep 2017 10:53:10 +0900 Subject: [PATCH 10/13] Revert "Unwrap" This reverts commit 1ef7e71d257a13257d712a52a27aef1cd20498d5. --- articles/051_actions.md | 97 +++++++++++++++++++++++++++++++---------- 1 file changed, 74 insertions(+), 23 deletions(-) diff --git a/articles/051_actions.md b/articles/051_actions.md index f93d6c8d6..de8f5462e 100644 --- a/articles/051_actions.md +++ b/articles/051_actions.md @@ -20,15 +20,30 @@ Original Author: {{ page.author }} ## Background -ROS services, which provide synchronous Remote Procedure Calls, are a useful concept for sending a request and getting a rapid reply. But in robotics there are many instances where a reply may take a significant length of time. Additionally, there are occasions when it is useful to send a request to do some processing or perform some action in the world, where the result is less important than the effect of carrying it out. The progress of such requests often needs to be tracked, success or failure must be known in addition to receiving back information produced, and the request may need to be cancelled or altered before it completes. These requirements cannot be fulfilled by a simple RPC mechanism, whether or not it is asynchronous. - -To satisfy these use cases, ROS provides a third communication paradigm known as "actions". An action is a goal-oriented request that occurs asynchronously to the requester, is typically (but not necessarily) longer-running than immediate, can be cancelled or replaced during execution, and has a server that provides feedback on execution progress. - -This document defines how actions are specified, what they look like to ROS users (both node developers and system integrators) +ROS services, which provide synchronous Remote Procedure Calls, are a useful +concept for sending a request and getting a rapid reply. But in robotics there +are many instances where a reply may take a significant length of time. +Additionally, there are occasions when it is useful to send a request to +do some processing or perform some action in the world, where the result is +less important than the effect of carrying it out. The progress of such +requests often needs to be tracked, success or failure must be known in +addition to receiving back information produced, and the request may need to be +cancelled or altered before it completes. These requirements cannot be +fulfilled by a simple RPC mechanism, whether or not it is asynchronous. + +To satisfy these use cases, ROS provides a third communication paradigm known +as "actions". An action is a goal-oriented request that occurs asynchronously +to the requester, is typically (but not necessarily) longer-running than +immediate, can be cancelled or replaced during execution, and has a server that +provides feedback on execution progress. + +This document defines how actions are specified, what they look like to ROS +users (both node developers and system integrators) ## Action specification -Actions are specified using a form of the ROS Message IDL. The specification contains three sections, each of which is a message specification: +Actions are specified using a form of the ROS Message IDL. The specification +contains three sections, each of which is a message specification: 1. Goal @@ -40,7 +55,8 @@ Any of these sections may be empty. Between the three sections is a line containing three hyphens, `---`. -Action specifications are stored in a file ending in `.action`. There is one action specification per `.action` file. +Action specifications are stored in a file ending in `.action`. There is one +action specification per `.action` file. An example action specification [taken from the actionlib wiki] is shown below. @@ -58,13 +74,29 @@ uint32 number_dishes_cleaned ## Serving and using actions -Actions are a first-class citizen in the ROS API, alongside topics and services. - -Action clients will use an API that provides a proxy object for the action. This will be a templated class, using the action class generated from the action specification as the template parameter. The client shall create an instance of this class, providing the address of the intended action server. Each instance of this class can only be related to one action server. Methods of the class will provide facilities for sending a goal to the action server, receiving a result, and getting feedback. - -Action servers will use an API that provides a templated server class, using the action class generated from the action specification as the template parameter. The node implementer will create a function that implements the action's behaviour, create an instance of the templated server class, and bind the implementing function to the server. The implementing function will receive as one of its parameters the received goal message, and as another parameter the action server instance. The implementation shall use the action server instance to provide progress feedback and to report the result and success/failure/error status of the action's execution. - -Actions may be used from or served by real-time nodes. Therefore the actions API must be real-time capable. +Actions are a first-class citizen in the ROS API, alongside topics and +services. + +Action clients will use an API that provides a proxy object for the action. +This will be a templated class, using the action class generated from the +action specification as the template parameter. The client shall create an +instance of this class, providing the address of the intended action server. +Each instance of this class can only be related to one action server. Methods +of the class will provide facilities for sending a goal to the action server, +receiving a result, and getting feedback. + +Action servers will use an API that provides a templated server class, using +the action class generated from the action specification as the template +parameter. The node implementer will create a function that implements the +action's behaviour, create an instance of the templated server class, and bind +the implementing function to the server. The implementing function will receive +as one of its parameters the received goal message, and as another parameter +the action server instance. The implementation shall use the action server +instance to provide progress feedback and to report the result and +success/failure/error status of the action's execution. + +Actions may be used from or served by real-time nodes. Therefore the actions +API must be real-time capable. ## Introspection tools @@ -72,9 +104,12 @@ Actions, like topics and services, are introspectable from the command line. In ROS 1, actions are visible in the output of the `rostopic` tool. -In ROS 2, actions will not be visible as a set of topics. Nor will they be visible as a set of services [in the case that services be used to implement them]. They will be visible using a separate `ros2 action` command line tool. +In ROS 2, actions will not be visible as a set of topics. Nor will they be +visible as a set of services [in the case that services be used to implement +them]. They will be visible using a separate `ros2 action` command line tool. -The command line tool will be similar to the `ros2 service` tool. It will be able to: +The command line tool will be similar to the `ros2 service` tool. It will be +able to: - list known actions, - display the arguments for an action's goal, @@ -82,14 +117,30 @@ The command line tool will be similar to the `ros2 service` tool. It will be abl - display information about the server of an action, - display the underlying topics and/or services providing the action, - find actions by action type, and -- call an action, display feedback as it is received, display the result when received, and cancel the action (when the tool is terminated prematurely) +- call an action, display feedback as it is received, display the result when + received, and cancel the action (when the tool is terminated prematurely) -Each action, despite using multiple topics and/or services in its implementation, will be listed and treated as a single unit by this tool. [This will probably be a namespace that contains the underlying topics, etc.] +Each action, despite using multiple topics and/or services in its +implementation, will be listed and treated as a single unit by this tool. [This +will probably be a namespace that contains the underlying topics, etc.] ## Middleware implementation -In ROS 1, actions are implemented using a set of topics under a namespace taken from the action name. This implementation was chosen because ROS services are inherently synchronous, and so incompatible with the asynchronous nature of the action concept. There is also a need for a status/feedback channel and a control channel. - -The Remote Procedure Call over DDS (DDS-RPC) specification does not explicitly provide facilities for interrupting service calls or receiving feedback on their progress. It does provide for receiving both a return value from a request and, at the same time, an indication of whether the request was successful or raised an exception, with the exception type included in this information. - -This means that an implementation of actions cannot simply be a DDS-style RPC. The implementation must separately provide status/feedback and control channels. While a control channel could be implemented as a separate RPC, due to the dataflow nature of feedback it would be best implemented as a separate topic. +In ROS 1, actions are implemented using a set of topics under a namespace taken +from the action name. This implementation was chosen because ROS services are +inherently synchronous, and so incompatible with the asynchronous nature of the +action concept. There is also a need for a status/feedback channel and a +control channel. + +The Remote Procedure Call over DDS (DDS-RPC) specification does not explicitly +provide facilities for interrupting service calls or receiving feedback on +their progress. It does provide for receiving both a return value from a +request and, at the same time, an indication of whether the request was +successful or raised an exception, with the exception type included in this +information. + +This means that an implementation of actions cannot simply be a DDS-style RPC. +The implementation must separately provide status/feedback and control +channels. While a control channel could be implemented as a separate RPC, due +to the dataflow nature of feedback it would be best implemented as a separate +topic. From f65f48d0ff430c624190b6542356e575fb366d7f Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Wed, 6 Sep 2017 10:53:29 +0900 Subject: [PATCH 11/13] Revert "Start of article about actions" This reverts commit 7a7a72d3949a648858aaf7b5ead8b402a1d51450. --- articles/051_actions.md | 146 ---------------------------------------- 1 file changed, 146 deletions(-) delete mode 100644 articles/051_actions.md diff --git a/articles/051_actions.md b/articles/051_actions.md deleted file mode 100644 index de8f5462e..000000000 --- a/articles/051_actions.md +++ /dev/null @@ -1,146 +0,0 @@ ---- -layout: default -title: Actions -permalink: articles/actions.html -abstract: - Despite their implementation as a separate library and lack of a detailed specification, actions are one of the three core types of interaction between ROS nodes. Their asynchronous nature combined with the feedback and control mechanism gives them significantly more power than a standard RPC. This article formalises the requirements for actions, including what a ROS user should see and what the middleware layer should provide. -author: '[Geoffrey Biggs](https://github.com/gbiggs)' -published: true ---- - -{:toc} - -# {{ page.title }} - -
-{{ page.abstract }} -
- -Original Author: {{ page.author }} - -## Background - -ROS services, which provide synchronous Remote Procedure Calls, are a useful -concept for sending a request and getting a rapid reply. But in robotics there -are many instances where a reply may take a significant length of time. -Additionally, there are occasions when it is useful to send a request to -do some processing or perform some action in the world, where the result is -less important than the effect of carrying it out. The progress of such -requests often needs to be tracked, success or failure must be known in -addition to receiving back information produced, and the request may need to be -cancelled or altered before it completes. These requirements cannot be -fulfilled by a simple RPC mechanism, whether or not it is asynchronous. - -To satisfy these use cases, ROS provides a third communication paradigm known -as "actions". An action is a goal-oriented request that occurs asynchronously -to the requester, is typically (but not necessarily) longer-running than -immediate, can be cancelled or replaced during execution, and has a server that -provides feedback on execution progress. - -This document defines how actions are specified, what they look like to ROS -users (both node developers and system integrators) - -## Action specification - -Actions are specified using a form of the ROS Message IDL. The specification -contains three sections, each of which is a message specification: - -1. Goal - -1. Result - -1. Feedback - -Any of these sections may be empty. - -Between the three sections is a line containing three hyphens, `---`. - -Action specifications are stored in a file ending in `.action`. There is one -action specification per `.action` file. - -An example action specification [taken from the actionlib wiki] is shown below. - -``` -# Define the goal -uint32 dishwasher_id # Specify which dishwasher we want to use ---- -# Define the result -uint32 total_dishes_cleaned ---- -# Define a feedback message -float32 percent_complete -uint32 number_dishes_cleaned -``` - -## Serving and using actions - -Actions are a first-class citizen in the ROS API, alongside topics and -services. - -Action clients will use an API that provides a proxy object for the action. -This will be a templated class, using the action class generated from the -action specification as the template parameter. The client shall create an -instance of this class, providing the address of the intended action server. -Each instance of this class can only be related to one action server. Methods -of the class will provide facilities for sending a goal to the action server, -receiving a result, and getting feedback. - -Action servers will use an API that provides a templated server class, using -the action class generated from the action specification as the template -parameter. The node implementer will create a function that implements the -action's behaviour, create an instance of the templated server class, and bind -the implementing function to the server. The implementing function will receive -as one of its parameters the received goal message, and as another parameter -the action server instance. The implementation shall use the action server -instance to provide progress feedback and to report the result and -success/failure/error status of the action's execution. - -Actions may be used from or served by real-time nodes. Therefore the actions -API must be real-time capable. - -## Introspection tools - -Actions, like topics and services, are introspectable from the command line. - -In ROS 1, actions are visible in the output of the `rostopic` tool. - -In ROS 2, actions will not be visible as a set of topics. Nor will they be -visible as a set of services [in the case that services be used to implement -them]. They will be visible using a separate `ros2 action` command line tool. - -The command line tool will be similar to the `ros2 service` tool. It will be -able to: - -- list known actions, -- display the arguments for an action's goal, -- display the type of an action's feedback and result, -- display information about the server of an action, -- display the underlying topics and/or services providing the action, -- find actions by action type, and -- call an action, display feedback as it is received, display the result when - received, and cancel the action (when the tool is terminated prematurely) - -Each action, despite using multiple topics and/or services in its -implementation, will be listed and treated as a single unit by this tool. [This -will probably be a namespace that contains the underlying topics, etc.] - -## Middleware implementation - -In ROS 1, actions are implemented using a set of topics under a namespace taken -from the action name. This implementation was chosen because ROS services are -inherently synchronous, and so incompatible with the asynchronous nature of the -action concept. There is also a need for a status/feedback channel and a -control channel. - -The Remote Procedure Call over DDS (DDS-RPC) specification does not explicitly -provide facilities for interrupting service calls or receiving feedback on -their progress. It does provide for receiving both a return value from a -request and, at the same time, an indication of whether the request was -successful or raised an exception, with the exception type included in this -information. - -This means that an implementation of actions cannot simply be a DDS-style RPC. -The implementation must separately provide status/feedback and control -channels. While a control channel could be implemented as a separate RPC, due -to the dataflow nature of feedback it would be best implemented as a separate -topic. From 6b16ec623b7ec38e000028cac00d0314a9d9752a Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Wed, 6 Sep 2017 10:55:36 +0900 Subject: [PATCH 12/13] Switch to upstream version of node_lifecycle.md --- articles/node_lifecycle.md | 192 ++++++------------------------------- 1 file changed, 28 insertions(+), 164 deletions(-) diff --git a/articles/node_lifecycle.md b/articles/node_lifecycle.md index fd5ec28d7..d6e0715f6 100644 --- a/articles/node_lifecycle.md +++ b/articles/node_lifecycle.md @@ -53,17 +53,14 @@ There are also 6 transition states which are intermediate states during a reques In the transitions states logic will be executed to determine if the transition is successful. Success or failure shall be communicated to lifecycle management software through the lifecycle management interface. -There are 5 transitions exposed to a supervisory process, they are: +There are 7 transitions exposed to a supervisory process, they are: +- `create` - `configure` - `cleanup` - `activate` - `deactive` - `shutdown` - -Additionally, there are two transitions that may be exposed by a supervisory process if dynamic creation and destruction of nodes is supported by that supervisory process. - -- `create` - `destroy` The behavior of each state is as defined below. @@ -199,18 +196,6 @@ Transitions to `ErrorProcessing` may be caused by error return codes in callback - If the `onShutdown` callback raises or results in any other result code the node will transition to `Finalized`. -## Use of a supervisory process - -Managed nodes may be instantiated manually by a developer. -In this case, the developer's own code is responsible for creating and destroying the node. -However, the node may alternatively be owned by a container system. -The container will be responsible for creating and destroying the node. -Such a container will be responsible for exposing the following two transitions. - -### Create Transition - -This transition will instantiate the node, but will not run any code beyond the constructor. - ### Destroy Transition This transition will simply cause the deallocation of the node. @@ -218,165 +203,44 @@ In an object oriented environment it may just involve invoking the destructor. Otherwise it will invoke a standard deallocation method. This transition should always succeed. -## Management Interface - -A node that has a managed life cycle complying with the above life cycle shall provide the following interface via ROS topics and services. -This interface is to be used by tools to manage the node's life cycle state transitions, either automatically or manually according to the tool's purpose. - -The topics and services of this interface shall function in all states of the node's life cycle. -They shall not be disabled by the node shifting to the `Inactive` state, for example. - -### Interface namespace - -The interface shall be provided in a namespace named "_infra/lifecycle" underneath the node's namespace. - -For example, if a node named `talker` has a managed life cycle complying with the state machine described above, it shall provide topics under the namespace `/talker/_infra/lifecycle`. - -All examples in the following sections are also given assuming a node named `talker`. - -If the `_infra/lifecycle` namespace is available under a node's namespace, then that node shall be assumed to be functioning according to the managed life cycle. -If the node is not functioning according to the managed life cycle, the `_infra/lifecycle` namespace shall not exist. -In other words, tooling shall judge if a node is managed or not by the presence of the `_infra/lifecycle` namespace. - -### State enumerations - -The messages used by the interface shall use the following enumeration for indicating states. - - # Primary states - uint8 PRIMARY_STATE_UNKNOWN = 0 - uint8 PRIMARY_STATE_UNCONFIGURED = 1 - uint8 PRIMARY_STATE_INACTIVE = 2 - uint8 PRIMARY_STATE_ACTIVE = 3 - uint8 PRIMARY_STATE_FINALIZED = 4 - - # Temporary intermediate states - uint8 TRANSITION_STATE_CONFIGURING = 10 - uint8 TRANSITION_STATE_CLEANINGUP = 11 - uint8 TRANSITION_STATE_SHUTTINGDOWN = 12 - uint8 TRANSITION_STATE_ACTIVATING = 13 - uint8 TRANSITION_STATE_DEACTIVATING = 14 - uint8 TRANSITION_STATE_ERRORPROCESSING = 15 - - uint8 id - string label - -See for example the [message definition used by `RCL`](https://raw.githubusercontent.com/ros2/rcl_interfaces/master/lifecycle_msgs/msg/State.msg). - -### Life cycle state changes topic - -When the node's life cycle changes, it shall broadcast the following message on the `_infra/lifecycle/state_change` topic. - - uint8 previous_state - uint8 next_state - string trigger - -`trigger` may be filled in containing a reason for the life cycle change. -This value is optional. - -This topic must at a minimum make the most recent message available to new subscribers at all times. -This may be achieved by use of appropriate QoS settings. - -For example, if the `talker` node transitions from the `Active` state to the `Finalised` state via the `ShuttingDown` state in response to an external request to shut down the node, it will produce the following sequence of messages on this topic (values for `trigger` are illustrative only): - - previous_state = INACTIVE - next_state = SHUTTTING_DOWN - trigger = "shutdown request" - - previous_state = SHUTTING_DOWN - next_state = FINALIZED - trigger = "shutdown returned OK" - -If the `talker` node transitions from the `Inactive` state to the `Unconfigured` state via a request to activate the node and an error occurring in activation processing, it will produce the following sequence of messages: - - previous_state = INACTIVE - next_state = ACTIVATING - trigger = "activate request" - - previous_state = ACTIVATING - next_state = ERROR_PROCESSING - trigger = "error in activating state" - - previous_state = ERROR_PROCESSING - next_state = UNCONFIGURED - trigger = "error processing returned OK" - -### Current life cycle state service - -The node's current life cycle state shall be available via the `_infra/lifecycle/get_state` service. -The service definition is: - - --- - uint8 state - string state_name - -`state_name` must assume one of the following values, according to the value of `state`. - - Value of state | Value of state_name - UNKNOWN | unknown - UNCONFIGURED | unconfigured - INACTIVE | inactive - ACTIVE | active - FINALIZED | finalized - CONFIGURING | configuring - CLEANING_UP | cleaning_up - SHUTTING_DOWN | shutting_down - ACTIVATING | activating - DEACTIVATING | deactivating - ERROR_PROCESSING | error_processing - -The `UNKNOWN`/`unknown` value shall be assumed by clients of the service to indicate that the node is in an unknown state and thus unusable. - -### Transition request service - -The service `_infra/lifecycle/change_state` service shall be provided by the life cycle interface. - -When this service call is received, the node's life cycle state shall be shifted to the requested state via any appropriate intermediate states in accordance with the state diagram shown above. - -For example, if the node is in the `Inactive` state and a request is made to shift to the `Active` state, the node's life cycle shall first be shifted to the `Activating` state. -Based on the result of the `onActivate()` function called during the `Activating` state, the node's life cycle shall then shift to either the `Active` state or the `ErrorProcessing` state. +### Create Transition -The service definition is: +This transition will instantiate the node, but will not run any code beyond the constructor. - # Allowable transitions - uint8 CONFIGURE=0 - uint8 CLEANUP=1 - uint8 ACTIVATE=2 - uint8 DEACTIVATE=3 - uint8 SHUTDOWN=4 - # Transition results - uint8 TRANSITION_ERROR=0 - uint8 SUCCESS=1 - uint8 WRONG_PREV_STATE=10 +## Management Interface +A managed node will be exposed to the ROS ecosystem by the following interface, as seen by tools that perform the managing. +This interface should not be subject to the restrictions on communications imposed by the lifecycle states. - uint8 transition - --- - uint8 result +It is expected that a common pattern will be to have a container class which loads a managed node implementation from a library and through a plugin architecture automatically exposes the required management interface via methods and the container is not subject to the lifecycle management. +However, it is fully valid to consider any implementation which provides this interface and follows the lifecycle policies a managed node. +Conversely, any object that provides these services but does not behave in the way defined in the life cycle state machine is malformed. -`transition` must take one of the values defined in the transitions enumeration. -Additionally, the allowable values for `transition` is determined by the current life cycle state. -`transition` must take one of the following values, depending on the current life cycle state. +These services may also be provided via attributes and method calls (for local management) in addition to being exposed ROS messages and topics/services (for remote management). +In the case of providing a ROS middleware interface, specific topics must be used, and they should be placed in a suitable namespace. - Current state | `transition` allowable values - Unconfigured | `CONFIGURE`, `SHUTDOWN` - Inactive | `ACTIVATE`, `CLEANUP`, `SHUTDOWN` - Active | `DEACTIVATE`, `SHUTDOWN` - Finalized | None +Each possible supervisory transition will be provides as a service by the name of the transition except `create`. +`create` will require an extra argument for finding the node to instantiate. +The service will report whether the transition was successfully completed. -`result` shall be `SUCCESS` if the node's life cycle successfully moved to the requested state and the results of any intermediate state functions were all `success`. +### Lifecycle events -`result` shall be `TRANSITION_ERROR` if the result of any intermediate state function was anything other than `success` or an error was reported by any other means, and the node is now in the `ErrorProcessing` state or one of its successor states. +A topic should be provided to broadcast the new life cycle state when it changes. +This topic must be latched. +The topic must be named `lifecycle_state` it will carry both the end state and the transition, with result code. +It will publish ever time that a transition is triggered, whether successful or not. -`result` shall be `WRONG_PREV_STATE` if the node's life cycle is not in the correct predecessor state for the requested transition, as described above. +## Node Management -### Provision of the interface +There are several different ways in which a managed node may transition between states. +Most state transitions are expected to be coordinated by an external management tool which will provide the node with it's configuration and start it. +The external management tool is also expected monitor it and execute recovery behaviors in case of failures. +A local management tool is also a possibility, leveraging method level interfaces. +And a node could be configured to self manage, however this is discouraged as this will interfere with external logic trying to managed the node via the interface. -What provides the interface is implementation dependent. -It may be provided directly by the node object itself, by a container object, or by any other means as appropriate to the technologies being used to implement the node and ROS infrastructure. +There is one transition expected to originate locally, which is the `ERROR` transition. -It is expected that a common pattern will be to have a container class which loads a managed node implementation from a library and through a plugin architecture automatically exposes the required management interface via methods and the container is not subject to the lifecycle management. -However, it is fully valid to consider any implementation which provides this interface and follows the lifecycle policies a managed node. -Conversely, any object that provides these services but does not behave in the way defined in the life cycle state machine is malformed. +A managed node may also want to expose arguments to automatically configure and activate when run in an unmanaged system. ## Extensions From 72591bcef238c7cefff2ded97db9bc8c7caae739 Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Wed, 6 Sep 2017 10:55:56 +0900 Subject: [PATCH 13/13] Start of article about actions --- articles/051_actions.md | 95 +++++++++++++++++++++++++++++++++++++++++ 1 file changed, 95 insertions(+) create mode 100644 articles/051_actions.md diff --git a/articles/051_actions.md b/articles/051_actions.md new file mode 100644 index 000000000..f93d6c8d6 --- /dev/null +++ b/articles/051_actions.md @@ -0,0 +1,95 @@ +--- +layout: default +title: Actions +permalink: articles/actions.html +abstract: + Despite their implementation as a separate library and lack of a detailed specification, actions are one of the three core types of interaction between ROS nodes. Their asynchronous nature combined with the feedback and control mechanism gives them significantly more power than a standard RPC. This article formalises the requirements for actions, including what a ROS user should see and what the middleware layer should provide. +author: '[Geoffrey Biggs](https://github.com/gbiggs)' +published: true +--- + +{:toc} + +# {{ page.title }} + +
+{{ page.abstract }} +
+ +Original Author: {{ page.author }} + +## Background + +ROS services, which provide synchronous Remote Procedure Calls, are a useful concept for sending a request and getting a rapid reply. But in robotics there are many instances where a reply may take a significant length of time. Additionally, there are occasions when it is useful to send a request to do some processing or perform some action in the world, where the result is less important than the effect of carrying it out. The progress of such requests often needs to be tracked, success or failure must be known in addition to receiving back information produced, and the request may need to be cancelled or altered before it completes. These requirements cannot be fulfilled by a simple RPC mechanism, whether or not it is asynchronous. + +To satisfy these use cases, ROS provides a third communication paradigm known as "actions". An action is a goal-oriented request that occurs asynchronously to the requester, is typically (but not necessarily) longer-running than immediate, can be cancelled or replaced during execution, and has a server that provides feedback on execution progress. + +This document defines how actions are specified, what they look like to ROS users (both node developers and system integrators) + +## Action specification + +Actions are specified using a form of the ROS Message IDL. The specification contains three sections, each of which is a message specification: + +1. Goal + +1. Result + +1. Feedback + +Any of these sections may be empty. + +Between the three sections is a line containing three hyphens, `---`. + +Action specifications are stored in a file ending in `.action`. There is one action specification per `.action` file. + +An example action specification [taken from the actionlib wiki] is shown below. + +``` +# Define the goal +uint32 dishwasher_id # Specify which dishwasher we want to use +--- +# Define the result +uint32 total_dishes_cleaned +--- +# Define a feedback message +float32 percent_complete +uint32 number_dishes_cleaned +``` + +## Serving and using actions + +Actions are a first-class citizen in the ROS API, alongside topics and services. + +Action clients will use an API that provides a proxy object for the action. This will be a templated class, using the action class generated from the action specification as the template parameter. The client shall create an instance of this class, providing the address of the intended action server. Each instance of this class can only be related to one action server. Methods of the class will provide facilities for sending a goal to the action server, receiving a result, and getting feedback. + +Action servers will use an API that provides a templated server class, using the action class generated from the action specification as the template parameter. The node implementer will create a function that implements the action's behaviour, create an instance of the templated server class, and bind the implementing function to the server. The implementing function will receive as one of its parameters the received goal message, and as another parameter the action server instance. The implementation shall use the action server instance to provide progress feedback and to report the result and success/failure/error status of the action's execution. + +Actions may be used from or served by real-time nodes. Therefore the actions API must be real-time capable. + +## Introspection tools + +Actions, like topics and services, are introspectable from the command line. + +In ROS 1, actions are visible in the output of the `rostopic` tool. + +In ROS 2, actions will not be visible as a set of topics. Nor will they be visible as a set of services [in the case that services be used to implement them]. They will be visible using a separate `ros2 action` command line tool. + +The command line tool will be similar to the `ros2 service` tool. It will be able to: + +- list known actions, +- display the arguments for an action's goal, +- display the type of an action's feedback and result, +- display information about the server of an action, +- display the underlying topics and/or services providing the action, +- find actions by action type, and +- call an action, display feedback as it is received, display the result when received, and cancel the action (when the tool is terminated prematurely) + +Each action, despite using multiple topics and/or services in its implementation, will be listed and treated as a single unit by this tool. [This will probably be a namespace that contains the underlying topics, etc.] + +## Middleware implementation + +In ROS 1, actions are implemented using a set of topics under a namespace taken from the action name. This implementation was chosen because ROS services are inherently synchronous, and so incompatible with the asynchronous nature of the action concept. There is also a need for a status/feedback channel and a control channel. + +The Remote Procedure Call over DDS (DDS-RPC) specification does not explicitly provide facilities for interrupting service calls or receiving feedback on their progress. It does provide for receiving both a return value from a request and, at the same time, an indication of whether the request was successful or raised an exception, with the exception type included in this information. + +This means that an implementation of actions cannot simply be a DDS-style RPC. The implementation must separately provide status/feedback and control channels. While a control channel could be implemented as a separate RPC, due to the dataflow nature of feedback it would be best implemented as a separate topic.