-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathtransition_ready_unit_tests.cpp
More file actions
266 lines (228 loc) · 12.6 KB
/
transition_ready_unit_tests.cpp
File metadata and controls
266 lines (228 loc) · 12.6 KB
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
#include <gtest/gtest.h> // googletest header file
#include <am_super/super_node_mediator.h>
using namespace std;
using namespace am;
/** Validates state transitions.
* https://automodality.atlassian.net/wiki/spaces/AMROS/pages/929234949/AMROS+System+States
*
*/
class TransitionReady : public ::testing::Test
{
protected:
SuperNodeMediator superNodeMediator;
TransitionReady() : superNodeMediator("am_super"){}
SuperNodeMediator::SuperNodeInfo manifested_online_node_fixture()
{
SuperNodeMediator::SuperNodeInfo node;
node.online = true;
node.manifested = true;
return node;
}
/**The main test method providing reuse for testing states. Overloaded methods are provided
* for ease of use.
*
* Three main tests are happening:
* 1. State transition if the check equals expected
* 2. State transition if the flight controller state matches desired states.
* 3. Lifecycle command provided for check failures that want to encourage re-issue
*/
void ASSERT_TRANSITION_READY(SuperNodeMediator superNodeMediator, SuperState from, LifeCycleState node_state,
SuperNodeMediator::SuperFltCtrlState flt_ctrl_state, bool expected_ready,
SuperState expected_state, bool expected_resend_life_cycle_command,
LifeCycleCommand life_cycle_command, OperatorCommand last_op_command_received = OperatorCommand::ARM,
ControllerState last_controller_state_received = SuperNodeMediator::StateTransition::NO_CONTROLLER_STATE,
bool status_error = false)
{
SuperNodeMediator::Supervisor supervisor;
supervisor.system_state = from;
supervisor.flt_ctrl_state = flt_ctrl_state;
supervisor.last_op_command_received = last_op_command_received;
supervisor.last_controller_state_received = last_controller_state_received;
supervisor.status_error = status_error;
{
SuperNodeMediator::SuperNodeInfo node = manifested_online_node_fixture();
node.state = node_state;
supervisor.nodes.insert({ "manresend_life_cycle_commandifested-node-name", node });
}
SuperNodeMediator::TransitionInstructions result = superNodeMediator.transitionReady(supervisor);
ASSERT_EQ(result.ready_for_transition, expected_ready);
if (result.ready_for_transition)
{
ASSERT_EQ(result.new_state, expected_state);
}
ASSERT_EQ(result.resend_life_cycle_command, expected_resend_life_cycle_command);
if (result.resend_life_cycle_command)
{
ASSERT_EQ(result.life_cycle_command, life_cycle_command);
}
}
/**When flight controller states are expected.*/
void ASSERT_TRANSITION_READY(SuperNodeMediator superNodeMediator, SuperState from, LifeCycleState node_state,
SuperNodeMediator::SuperFltCtrlState flt_ctrl_state, bool expected_ready,
SuperState expected_state)
{
ASSERT_TRANSITION_READY(superNodeMediator, from, node_state, flt_ctrl_state, expected_ready, expected_state, false,
(LifeCycleCommand)NULL);
}
/**For the simplest cases without flight controller or lifecycle commands*/
void ASSERT_TRANSITION_READY(SuperNodeMediator superNodeMediator, SuperState from, LifeCycleState node_state,
bool expected_ready, SuperState expected_state = SuperState::OFF)
{
ASSERT_TRANSITION_READY(superNodeMediator, from, node_state, (SuperNodeMediator::SuperFltCtrlState)NULL,
expected_ready, expected_state);
}
};
TEST_F(TransitionReady, transitionReady_BootingToReadyWhenAllNodesInactive)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::BOOTING, LifeCycleState::INACTIVE, true,
SuperState::READY);
}
TEST_F(TransitionReady, transitionReady_BootingNoTransitionWhenAllNodesAreActive)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::BOOTING, LifeCycleState::ACTIVE,
(SuperNodeMediator::SuperFltCtrlState)NULL, false, (SuperState)NULL, true,
LifeCycleCommand::CONFIGURE);
}
TEST_F(TransitionReady, transitionReady_BootingNoTransitionWhenNodesNotInactiveOrActive)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::BOOTING, LifeCycleState::UNCONFIGURED,
(SuperNodeMediator::SuperFltCtrlState)NULL, false, (SuperState)NULL, true,
LifeCycleCommand::CONFIGURE);
}
/**Not ready to transition from Ready so send another configure command */
TEST_F(TransitionReady, transitionReady_ReadyNoTransitionWhenNotArmed)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::READY, (LifeCycleState)NULL,
(SuperNodeMediator::SuperFltCtrlState)NULL, false, (SuperState)NULL, false,
LifeCycleCommand::CONFIGURE, OperatorCommand::LAUNCH);
}
TEST_F(TransitionReady, transitionReady_ReadyToArmingWhenArmed)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::READY, LifeCycleState::INACTIVE,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::ARMING, false,
LifeCycleCommand::CONFIGURE, OperatorCommand::ARM);
}
TEST_F(TransitionReady, transitionReady_ReadyToShutdownOnOpShutdown)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::READY, LifeCycleState::SHUTTING_DOWN,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::SHUTDOWN, false,
LifeCycleCommand::SHUTDOWN, OperatorCommand::SHUTDOWN);
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::READY, LifeCycleState::FINALIZED,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::SHUTDOWN, false,
LifeCycleCommand::SHUTDOWN, OperatorCommand::SHUTDOWN);
}
TEST_F(TransitionReady, transitionReady_ArmingToArmedWhenNodesActive)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::ARMING, LifeCycleState::ACTIVE, true, SuperState::ARMED);
}
TEST_F(TransitionReady, transitionReady_ArmingNoTransitionWhenNodesNotActive)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::ARMING, LifeCycleState::INACTIVE,
(SuperNodeMediator::SuperFltCtrlState)NULL, false, (SuperState)NULL, true,
LifeCycleCommand::ACTIVATE);
}
/* Enable when we implement multimap for SuperState to StateTransition*/
TEST_F(TransitionReady, DISABLED_transitionReady_ArmedToAbortWhenDectivated)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::ARMED, LifeCycleState::INACTIVE, true, SuperState::ABORT);
}
/* Enable when we implement multimap for SuperState to StateTransition*/
TEST_F(TransitionReady, DISABLED_transitionReady_ArmedNoTransitionRemainingActivated)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::ARMED, LifeCycleState::ACTIVE, false);
}
TEST_F(TransitionReady, transitionReady_ArmedToAutoWhenReadyToLaunchAndOperatorIsLaunching)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::ARMED, LifeCycleState::ACTIVE,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::AUTO,
false, (LifeCycleCommand)NULL, OperatorCommand::LAUNCH);
}
TEST_F(TransitionReady, transitionReady_AutoToSemiAutoOnPause)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::AUTO, LifeCycleState::ACTIVE,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::SEMI_AUTO,
false, (LifeCycleCommand)NULL, OperatorCommand::PAUSE);
}
TEST_F(TransitionReady, transitionReady_SemiAutoToAutoOnResume)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::SEMI_AUTO, LifeCycleState::ACTIVE,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::AUTO,
false, (LifeCycleCommand)NULL, OperatorCommand::RESUME);
}
TEST_F(TransitionReady, TransitionReady_AutoToAbortOnOperatorAbort)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::AUTO, LifeCycleState::ACTIVE,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::ABORT,
false, (LifeCycleCommand)NULL, OperatorCommand::ABORT);
}
TEST_F(TransitionReady, TransitionReady_AbortToManualOnOpManual)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::ABORT, LifeCycleState::ACTIVE,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::MANUAL,
true, LifeCycleCommand::DEACTIVATE, OperatorCommand::MANUAL);
}
TEST_F(TransitionReady, TransitionReady_SemiAutoToManualOnOpManual)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::SEMI_AUTO, LifeCycleState::ACTIVE,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::MANUAL,
true, LifeCycleCommand::DEACTIVATE, OperatorCommand::MANUAL);
}
TEST_F(TransitionReady, TransitionReady_AutoToManualOnOpManual)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::AUTO, LifeCycleState::ACTIVE,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::MANUAL,
true, LifeCycleCommand::DEACTIVATE, OperatorCommand::MANUAL);
}
TEST_F(TransitionReady, TransitionReady_ManualToDisarmingOnOpLanded)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::MANUAL, LifeCycleState::ACTIVE,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::DISARMING,
false, (LifeCycleCommand)NULL, SuperNodeMediator::StateTransition::NO_OPERATOR_COMMAND,
ControllerState::COMPLETED);
}
TEST_F(TransitionReady, TransitionReady_AbortToDisarmingOnControllerStateCompleted)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::ABORT, LifeCycleState::ACTIVE,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::DISARMING,
false, (LifeCycleCommand)NULL, SuperNodeMediator::StateTransition::NO_OPERATOR_COMMAND,
ControllerState::COMPLETED);
}
TEST_F(TransitionReady, TransitionReady_AnyStateToShutdownOnStatusError_AllNodesShuttingDownOrFinalized)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::BOOTING, LifeCycleState::FINALIZED,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::SHUTDOWN,
false, (LifeCycleCommand)NULL, SuperNodeMediator::StateTransition::NO_OPERATOR_COMMAND,
SuperNodeMediator::StateTransition::NO_CONTROLLER_STATE, true);
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::READY, LifeCycleState::SHUTTING_DOWN,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::SHUTDOWN,
false, (LifeCycleCommand)NULL, SuperNodeMediator::StateTransition::NO_OPERATOR_COMMAND,
SuperNodeMediator::StateTransition::NO_CONTROLLER_STATE, true);
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::ARMED, LifeCycleState::SHUTTING_DOWN,
(SuperNodeMediator::SuperFltCtrlState)NULL, true, SuperState::SHUTDOWN,
false, (LifeCycleCommand)NULL, SuperNodeMediator::StateTransition::NO_OPERATOR_COMMAND,
SuperNodeMediator::StateTransition::NO_CONTROLLER_STATE, true);
}
TEST_F(TransitionReady, DISABLED_transitionReady_AutoToAbortWhenDeactivated)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::AUTO, LifeCycleState::INACTIVE, true, SuperState::ABORT);
}
TEST_F(TransitionReady, DISABLED_transitionReady_ArmedNoTransitionWhenRemainingActive)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::AUTO, LifeCycleState::ACTIVE, false);
}
//======================= FLIGHT Controller States =====================================
TEST_F(TransitionReady, DISABLED_transitionReady_ArmedToAutoWhenFlightControllerIsAuto)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::ARMED, LifeCycleState::ACTIVE,
SuperNodeMediator::SuperFltCtrlState::AUTO, true, SuperState::AUTO);
}
TEST_F(TransitionReady, DISABLED_transitionReady_AutoToSemiAutoWhenFlightControllerIsHold)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::AUTO, LifeCycleState::ACTIVE,
SuperNodeMediator::SuperFltCtrlState::HOLD, true, SuperState::SEMI_AUTO);
}
TEST_F(TransitionReady, DISABLED_transitionReady_SemiAutoToAutoWhenFlightControllerIsHold)
{
ASSERT_TRANSITION_READY(superNodeMediator, SuperState::SEMI_AUTO, LifeCycleState::ACTIVE,
SuperNodeMediator::SuperFltCtrlState::AUTO, true, SuperState::AUTO);
}