1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
/*
* Copyright (C) 2024 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
use bevy_ecs::{
hierarchy::ChildOf,
prelude::{Commands, World},
world::CommandQueue,
};
use crate::{
Builder, BuilderScopeContext, DeliveryChoice, InputSlot, OperateScope, Output, ScopeEndpoints,
ScopeSettingsStorage, Service, ServiceBundle, StreamAvailability, StreamPack, WorkflowService,
WorkflowStorage,
};
mod internal;
/// Trait to allow workflows to be spawned from a [`Commands`] or a [`World`].
pub trait SpawnWorkflowExt {
/// Spawn a workflow.
///
/// * `build` - A function that takes in a [`Scope`] and a [`Builder`] to
/// build the workflow
///
/// If you want any particular settings for your workflow, specify that with
/// the return value of `build`. Returning nothing `()` will use default
/// workflow settings.
fn spawn_workflow<Request, Response, Streams, W>(
&mut self,
build: impl FnOnce(Scope<Request, Response, Streams>, &mut Builder) -> W,
) -> Service<Request, Response, Streams>
where
Request: 'static + Send + Sync,
Response: 'static + Send + Sync,
Streams: StreamPack,
W: Into<WorkflowSettings>;
/// Spawn a pure input/output (io) workflow with no streams. This is just a
/// convenience wrapper around `spawn_workflow` which usually allows you to
/// avoid specifying any generic parameters when there are no streams being
/// used.
fn spawn_io_workflow<Request, Response, W>(
&mut self,
build: impl FnOnce(Scope<Request, Response>, &mut Builder) -> W,
) -> Service<Request, Response>
where
Request: 'static + Send + Sync,
Response: 'static + Send + Sync,
W: Into<WorkflowSettings>,
{
self.spawn_workflow::<Request, Response, (), W>(build)
}
}
/// The internal interface of the scope, used to connect elements inside the
/// scope to the start, terminate, and stream operations of the scope.
pub struct Scope<Request, Response, Streams: StreamPack = ()> {
/// This output will fire off the request message that was sent into the
/// scope. This fires exactly once per session of the scope, and is used to
/// initiate the activity in the scope.
///
/// Connect this output to the [`InputSlot`] of whichever node or operation
/// you want to activate at the start of the scope.
pub start: Output<Request>,
/// The slot that the final output of the scope must connect into. Once you
/// provide an input into this slot, the entire session of the scope will
/// wind down. The input will be passed out of the scope once all
/// uninterruptible data flows within the scope have finished.
pub terminate: InputSlot<Response>,
/// The input slot(s) that receive data for the output streams of the scope.
/// You can feed data into these input slots at any time during the execution
/// of the workflow.
pub streams: Streams::StreamInputPack,
}
/// Settings that describe some aspects of a workflow's behavior.
#[derive(Default)]
pub struct WorkflowSettings {
delivery: DeliverySettings,
scope: ScopeSettings,
}
impl WorkflowSettings {
/// Use default workflow settings.
pub fn new() -> Self {
Self::default()
}
/// Make a workflow with serial delivery behavior.
pub fn serial() -> Self {
Self::default().with_delivery(DeliverySettings::Serial)
}
/// Make a workflow with parallel delivery behavior.
pub fn parallel() -> Self {
Self::default().with_delivery(DeliverySettings::Parallel)
}
pub fn with_delivery(mut self, delivery: DeliverySettings) -> Self {
self.delivery = delivery;
self
}
pub fn delivery(&self) -> &DeliverySettings {
&self.delivery
}
pub fn delivery_mut(&mut self) -> &mut DeliverySettings {
&mut self.delivery
}
pub fn with_scope(mut self, scope: ScopeSettings) -> Self {
self.scope = scope;
self
}
pub fn scope(&self) -> &ScopeSettings {
&self.scope
}
pub fn scope_mut(&mut self) -> &mut ScopeSettings {
&mut self.scope
}
/// Transform the settings to be uninterruptible
pub fn uninterruptible(mut self) -> Self {
self.scope.set_uninterruptible(true);
self
}
}
impl From<()> for WorkflowSettings {
fn from(_: ()) -> Self {
WorkflowSettings::default()
}
}
impl From<ScopeSettings> for WorkflowSettings {
fn from(value: ScopeSettings) -> Self {
WorkflowSettings::new().with_scope(value)
}
}
impl From<DeliverySettings> for WorkflowSettings {
fn from(value: DeliverySettings) -> Self {
WorkflowSettings::new().with_delivery(value)
}
}
/// Settings which determine how the workflow delivers its requests: in serial
/// (handling one request at a time) or in parallel (allowing multiple requests
/// at a time).
#[derive(Default)]
pub enum DeliverySettings {
/// This workflow can only run one session at a time. If a new request comes
/// in for this workflow when the workflow is already being used, either
/// * the new request will be queued until the current request is finished, or
/// * the current request will be cancelled ([`Supplanted`][1]) so the new request can begin
///
/// [1]: crate::Supplanted
Serial,
/// The workflow can run any number of sessions at a time. If multiple
/// requests with the same [`DeliveryLabelId`][1] try to run at the same time,
/// those requests will follow the serial delivery behavior.
///
/// [1]: crate::DeliveryLabelId
#[default]
Parallel,
}
/// Settings which determine how the top-level scope of the workflow behaves.
#[cfg_attr(
feature = "diagram",
derive(serde::Serialize, serde::Deserialize, schemars::JsonSchema),
serde(rename_all = "snake_case")
)]
#[derive(Default, Clone, Debug)]
pub struct ScopeSettings {
/// Should we prevent the scope from being interrupted (e.g. cancelled)?
/// False by default, meaning by default scopes can be cancelled or
/// interrupted.
uninterruptible: bool,
}
impl ScopeSettings {
/// Make a new [`ScopeSettings`] with default values.
pub fn new() -> Self {
Self::default()
}
/// Make a new [`ScopeSettings`] for an uninterruptible scope.
pub fn uninterruptible() -> Self {
Self {
uninterruptible: true,
}
}
/// Check if the scope will be set to uninterruptible.
pub fn is_uninterruptible(&self) -> bool {
self.uninterruptible
}
/// Set whether the scope will be set to uninterruptible.
pub fn set_uninterruptible(&mut self, uninterruptible: bool) {
self.uninterruptible = uninterruptible;
}
}
impl From<()> for ScopeSettings {
fn from(_: ()) -> Self {
ScopeSettings::default()
}
}
impl<'w, 's> SpawnWorkflowExt for Commands<'w, 's> {
fn spawn_workflow<Request, Response, Streams, Settings>(
&mut self,
build: impl FnOnce(Scope<Request, Response, Streams>, &mut Builder) -> Settings,
) -> Service<Request, Response, Streams>
where
Request: 'static + Send + Sync,
Response: 'static + Send + Sync,
Streams: StreamPack,
Settings: Into<WorkflowSettings>,
{
let scope_id = self.spawn(()).id();
let ScopeEndpoints {
terminal,
enter_scope,
finish_scope_cancel,
} = OperateScope::add::<Request, Response>(None, scope_id, None, self);
let mut builder = Builder {
context: BuilderScopeContext {
scope: scope_id,
finish_scope_cancel,
},
commands: self,
};
let streams = Streams::spawn_workflow_streams(&mut builder);
let scope = Scope {
start: Output::new(scope_id, enter_scope),
terminate: InputSlot::new(scope_id, terminal),
streams,
};
let settings: WorkflowSettings = build(scope, &mut builder).into();
let mut stream_availability = StreamAvailability::default();
Streams::set_stream_availability(&mut stream_availability);
let mut service = self.spawn((
ServiceBundle::<WorkflowService<Request, Response, Streams>>::new(),
WorkflowStorage::new(scope_id),
stream_availability,
));
settings
.delivery
.apply_entity_commands::<Request>(&mut service);
let service = service.id();
self.entity(scope_id)
.insert(ScopeSettingsStorage(settings.scope))
.insert(ChildOf(service));
WorkflowService::<Request, Response, Streams>::cast(service)
}
}
impl SpawnWorkflowExt for World {
fn spawn_workflow<Request, Response, Streams, W>(
&mut self,
build: impl FnOnce(Scope<Request, Response, Streams>, &mut Builder) -> W,
) -> Service<Request, Response, Streams>
where
Request: 'static + Send + Sync,
Response: 'static + Send + Sync,
Streams: StreamPack,
W: Into<WorkflowSettings>,
{
let mut command_queue = CommandQueue::default();
let mut commands = Commands::new(&mut command_queue, self);
let service = commands.spawn_workflow(build);
command_queue.apply(self);
service
}
}
#[cfg(test)]
mod tests {
use crate::testing::*;
#[test]
fn test_simple_workflows() {
let mut context = TestingContext::minimal_plugins();
let workflow = context.spawn_io_workflow(|scope, builder| {
builder
.chain(scope.start)
.map_block(add)
.connect(scope.terminate);
});
let r = context.resolve_request((2.0, 2.0), workflow);
assert_eq!(r, 4.0);
let workflow = context.spawn_io_workflow(|scope, builder| {
let add_node = builder.create_map_block(add);
builder.connect(scope.start, add_node.input);
builder.connect(add_node.output, scope.terminate);
});
let r = context.resolve_request((3.0, 3.0), workflow);
assert_eq!(r, 6.0);
}
}