This robot example, originally from a tutorial of PRISM (see here for more information about the example), aims to show how to model and verify the probabilistic behaviour of an internal mail delivery robot.
The original PRISM model consists of three modules:
controller
for robot movements,battery
for charge of the battery,task
for handling of tasks and task completion.The map of the workplace is shown below.
This version uses a multi-way synchronisation of the move
event, but the multi-way synchronisation is not supported in RoboChart yet. Please see V2 for another model that uses two-way synchronisation only.
Accordingly, our RoboChart model is also composed of three state machines too:
movingSTM
for movements,batterySTM
for charge of the battery,taskSTM
for task management.The overall behaviour of the robot is specified by a controller deliverCTRL
.
The controller declares two constants
batteryCharge
: initial capacity of the battery,chargeSpeed
: charge speed of the battery,and two variables
p
: current location of the robot,c
: current level of the battery,to allow exchange of information between state machines. Additionally, an interface ctrlVarInf
is declared and it will be used in state machines.
As seen from the controller diagram, three state machines will synchronise on the move
event.
The movingSTM
state machine has one simple state Stuck
to denote the robot gets stuck and cannot move forward, and one composite state Move
to specify the movement behaviour from the initial location s0
. Inside Move
, it has nine sub-states from s0
to s8
that correspond to the nine locations in the map. Please note that each sub-state has an entry action (such as p=3
) to update the value of p
to its corresponding location. The probabilities of transitions between these sub-states are given by p{...}
.
A high-level transition from Move
to Stuck
(or Move
) via a junction provides a way for the robot to be in Stuck
(simutaneously set p
to 9) when it runs out of power and is not in the charge station 0
. Otherwise, it will re-enter the Move
and stay in the charge station.
The battery state machine batterySTM
only has one state s0
. s0
has two self-loop transitions:
p==0
), then the battery will be charged but it won’t exceed its capacity,p!=0
) and not out of power (c > 0
), every move
will cost it 1
unit of battery.The task state machine taskSTM
also has only one state s0
but it has more transitions:
FD_NoTask
) scheduled, then a new fetching location may be allocated with an equal probability (f/8
) and it is going to fetch the mail (FD_FetchMail
), or just stay in no task with a probability (1-f
);FD_NoTask
and its current location is not equal to new destination (g!=p
), the robot will continuously synchronise on move
(either charge or move to another location);g==p
), then it randomly chooses a destination with an equal probability of 1/7
except the fetching location. Additionally, it switches to the mail delivery (FD_DeliverMail
);g==p
) when it is in FD_DeliverMail
, it is back to FD_NoTask
and ready for the next task.Used configuration file.
pass
)!E [ F "deadlock" ]
Using the experiment
feature of PRISM to verify the property below by choosing x
ranging from 0 to 10 when batteryCharge=20
and chargeSpeed=4
,
const int x;
P=? [ F ctrl_ref0_deliverCTRL_p = x & ctrl_ref0_deliverCTRL_c=0 ]
the result is shown below.
We can see that it is highly possible that the robot gets stuck (p=9
).
Using the experiment
feature of PRISM to verify the property below by choosing x
ranging from 1 to 8 and batteryCharge
ranging from 10 to 30 while chargeSpeed
is set 4
const int x;
P=? [ F ctrl_ref0_deliverCTRL_p = x & ctrl_ref0_deliverCTRL_c=0 ]
the result is shown below.
Different bettary capacities have different impacts on the probability of running out of power in various locations.
If we fix the batteryCharge
to 20 but change chargeSpeed
from 2 to 6, the result is similar.
Add the following reward to the model,
rewards "nbmove"
[move_xxx_9] true : 1;
endrewards
and check the reward by the R
operator below.
R{"nbmove"}=? [ F ctrl_ref0_deliverCTRL_c=0 ]
The result is 31.68876486425289
.
Add a similar reward to the model,
rewards "nbdelivery"
[ctrl_ref0_deliverCTRL_stm_ref2_delivery] true : 1;
endrewards
and check the reward by the R
operator below.
R{"nbdelivery"}=? [ F ctrl_ref0_deliverCTRL_c=0 ]
The result is 0.5208043954240161
.
Using the CTL formula below, it is verified to be false
. In other words, there exists at least one path to make the robot always run and deliver the mail without being out of power and stuck.
A [ G F ctrl_ref0_deliverCTRL_stm_ref0_movingSTM_scpc=ctrl_ref0_deliverCTRL_stm_ref0_movingSTM_Stuck ]
But what’s the probability of not being stuck? It is 0.025714458225085668
.
P=? [ G ctrl_ref0_deliverCTRL_stm_ref0_movingSTM_scpc!=ctrl_ref0_deliverCTRL_stm_ref0_movingSTM_Stuck ]
Based on the observations about the three-way synchronisation of the model V1,
batterySTM
is always available for synchronisation on move
as long as moveSTM
is ready since each move
in moveSTM
has a guard condition c>0
. In other word, batterySTM
won’t prevent synchronisation but just uses synchronisation to update the current battery level c
.we can use two-way synchronisation only to update c
, instead of three-way synchronisation.
The RoboChart module deliverMOD
is shown below.
The platform deliverRP
provides two constants and two variables wrapped in an interface ctrlVarInf
. The controller deliverCTRL
synchronises with the platform on three events:
request
for the delivery request from the platform with a location parameter to indicate which office requests it,dest
for the delivery destination from the platform with a location parameter to indicate which office the delivery targets,delivered
for the notification from the controller to the platform to indicate the delivery is done.In stead of three-way synchronisation of the move
event, this model only uses two-way synchronisation that RoboChart is able to support now. We still use the move
event to synchronise between moveSTM
and taskSTM
as seen in the controller diagram below.
With regards to the synchronisation between moveSTM
and batterySTM
, we add two extra events upstart
and upend
to denote start and end of updates. For moveSTM
, we add an action upstart;upend
for each transition leaving from a probabilistic junction.
And for batterySTM
, we change its state machine as illustrated below.
These two events ensure that every move
will be followed by a upstart
and a upend
to update c
, then moveSTM
will update p
before the next synchronisation on move
.
The task state machine is given below.
Note that we use a different way (from the original PRISM model) to model the robot’s behaviour when it runs out of power at the charge station. The robot in the original model will get stuck, however, we still allow its battery to be charged if it runs out of power at the station. The behaviour is reflected by the synchronisation between the transitions from Move
to Move
via a junction in moveSTM
and the transition (modelling the charge of the battery) in batterySTM
.
Used configuration file.
constants C1:
deliverMOD::rp_ref0::batteryCapacity set to 20, and
deliverMOD::rp_ref0::chargeStep set to 4
constants C2:
deliverMOD::rp_ref0::batteryCapacity from set 8:20:4,
deliverMOD::rp_ref0::chargeStep set to 4
label l_stuck =
deliverMOD::ctrl_ref0::stm_ref0 is in
deliverMOD::ctrl_ref0::stm_ref0::Stuck
label l_batterystate =
deliverMOD::ctrl_ref0::stm_ref1 is in
deliverMOD::ctrl_ref0::stm_ref1::batteryState
label l_move =
deliverMOD::ctrl_ref0::stm_ref0 is in
deliverMOD::ctrl_ref0::stm_ref0::Move
label l_move_s0 =
deliverMOD::ctrl_ref0::stm_ref0::Move is in
deliverMOD::ctrl_ref0::stm_ref0::Move::s0
label l_move_s1 =
deliverMOD::ctrl_ref0::stm_ref0::Move is in
deliverMOD::ctrl_ref0::stm_ref0::Move::s1
label l_move_s2 =
deliverMOD::ctrl_ref0::stm_ref0::Move is in
deliverMOD::ctrl_ref0::stm_ref0::Move::s2
label l_move_s3 =
deliverMOD::ctrl_ref0::stm_ref0::Move is in
deliverMOD::ctrl_ref0::stm_ref0::Move::s3
label l_move_s4 =
deliverMOD::ctrl_ref0::stm_ref0::Move is in
deliverMOD::ctrl_ref0::stm_ref0::Move::s4
label l_move_s5 =
deliverMOD::ctrl_ref0::stm_ref0::Move is in
deliverMOD::ctrl_ref0::stm_ref0::Move::s5
label l_move_s6 =
deliverMOD::ctrl_ref0::stm_ref0::Move is in
deliverMOD::ctrl_ref0::stm_ref0::Move::s6
label l_move_s7 =
deliverMOD::ctrl_ref0::stm_ref0::Move is in
deliverMOD::ctrl_ref0::stm_ref0::Move::s7
label l_move_s8 =
deliverMOD::ctrl_ref0::stm_ref0::Move is in
deliverMOD::ctrl_ref0::stm_ref0::Move::s8
prob property P_deadlock_free:
!E [Finally "deadlock"]
with constants C1
rewards nbmove =
[deliverMOD::ctrl_ref0::stm_ref0::move] true : 1;
endrewards
prob property R_outofpower_moves:
Reward {nbmove} =? [
Reachable {deliverMOD::rp_ref0::c=0} && "l_batterystate"
]
with constants C2
rewards nbdelivery =
[deliverMOD::ctrl_ref0::stm_ref2::delivered] true : 1;
endrewards
prob property R_outofpower_deliveries:
Reward {nbdelivery} =? [
Reachable {deliverMOD::rp_ref0::c=0} && "l_batterystate"
]
with constant C2
prob property P_stuck_loc_0:
Prob=? [Finally {deliverMOD::rp_ref0::c=0}
&& "l_batterystate" && "l_move" && "l_move_s0"
]
with constant C1
prob property P_stuck_loc_1:
Prob=? [Finally {deliverMOD::rp_ref0::c=0}
&& "l_batterystate" && "l_move" && "l_move_s1"
]
with constant C1
prob property P_stuck_loc_2:
Prob=? [Finally {deliverMOD::rp_ref0::c=0}
&& "l_batterystate" && "l_move" && "l_move_s2"
]
with constant C1
prob property P_stuck_loc_3:
Prob=? [Finally {deliverMOD::rp_ref0::c=0}
&& "l_batterystate" && "l_move" && "l_move_s3"
]
with constant C1
prob property P_stuck_loc_4:
Prob=? [Finally {deliverMOD::rp_ref0::c=0}
&& "l_batterystate" && "l_move" && "l_move_s4"
]
with constant C1
prob property P_stuck_loc_5:
Prob=? [Finally {deliverMOD::rp_ref0::c=0}
&& "l_batterystate" && "l_move" && "l_move_s5"
]
with constant C1
prob property P_stuck_loc_6:
Prob=? [Finally {deliverMOD::rp_ref0::c=0}
&& "l_batterystate" && "l_move" && "l_move_s6"
]
with constant C1
prob property P_stuck_loc_7:
Prob=? [Finally {deliverMOD::rp_ref0::c=0}
&& "l_batterystate" && "l_move" && "l_move_s7"
]
with constant C1
prob property P_stuck_loc_8:
Prob=? [Finally {deliverMOD::rp_ref0::c=0}
&& "l_batterystate" && "l_move" && "l_move_s8"
]
with constant C1
prob property P_stuck_loc_9:
Prob=? [Finally {deliverMOD::rp_ref0::c=0}
&& "l_batterystate" && "l_stuck"
]
with constant C1
The verification results are displayed in the report below.
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
P_deadlock_free | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 0.029 seconds | true |
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
R_outofpower_moves | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=8 | 8983152 | 18618736 | 82.822 seconds | 14.075227429698785 |
R_outofpower_moves | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=12 | 14634096 | 30295664 | 183.529 seconds | 19.952926881030333 |
R_outofpower_moves | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=16 | 20285040 | 41972592 | 309.496 seconds | 25.793420816525206 |
R_outofpower_moves | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 460.928 seconds | 31.68848420483299 |
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
R_outofpower_deliveries | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=8 | 8983152 | 18618736 | 95.828 seconds | 0.6895273801121579 |
R_outofpower_deliveries | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=12 | 14634096 | 30295664 | 210.1 seconds | 0.8517713406202103 |
R_outofpower_deliveries | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=16 | 20285040 | 41972592 | 337.386 seconds | 1.0087499744621522 |
R_outofpower_deliveries | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 498.381 seconds | 1.1689687863444185 |
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
A_stuck | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 413.017 seconds | false |
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
P_stuck_loc_0 | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 460.773 seconds | 0.02567183864834713 |
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
P_stuck_loc_1 | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 477.005 seconds | 0.10795480852569778 |
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
P_stuck_loc_2 | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 491.92 seconds | 0.12917175436226516 |
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
P_stuck_loc_3 | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 495.315 seconds | 0.14039934198186033 |
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
P_stuck_loc_4 | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 474.077 seconds | 0.10107648905102322 |
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
P_stuck_loc_5 | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 531.203 seconds | 0.14377771389591754 |
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
P_stuck_loc_6 | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 492.263 seconds | 0.10795480831424162 |
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
P_stuck_loc_7 | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 494.472 seconds | 0.12917175377882492 |
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
P_stuck_loc_8 | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 514.503 seconds | 0.1403993411834904 |
Property | Const | Const | States | Transitions | Time | Result |
---|---|---|---|---|---|---|
P_stuck_loc_9 | deliverMOD::rp_ref0::chargeStep=4 | deliverMOD::rp_ref0::batteryCapacity=20 | 25935984 | 53649520 | 2.658 seconds | 1.0 |
The connections of events in the controller have been changed.
In this version, we change the direction of the connection upend
from moveSTM
to batterySTM
. This is due to the fact that a well-formedness condition has been strengthened and so the connection in V2 is no longer valid because a SendEvent statement like upend
in moveSTM
should be treated as events for output. If the direction isn’t changed, we have to use upend
in moveSTM
as input. For a simple event like this one, the only place is in the trigger of a transition. We change the direction and so upend
will be used in statements, the same as upstart
.
The moveSTM
is also changed.
We have one more state Update
in the Move
state. This change is based on an observation in V2 that many transitions in Move
have a very similar structure such as p{1/3}/upstart;upend
(only the differenece is the probability). So we can have only one probabilistic junction reused by all these states. Now each state in [s0
-s8
] has one outgoing transition to Update
with a trigger move
and a condition c>0
, then Update
has an action upstart;upend
leading to the probabilistic junction. From the junction, there is a transition to each state. The transition has only a probability and its value is a conditional depending on the current position of the robot (p
). We also make sure the summation of the probabilities from the junction is always equal to 1.0 no matter what p
is.
And for batterySTM
, we change its state machine as illustrated below, which is also due to the change of the direction of upend
.
Since upend
is used as input for batterySTM
, it could only be in a trigger. So we add a Update
state and its outgoing transition to batteryState
has the trigger upend
.
The task state machine is given below.
Used configuration file.
The verification results are displayed in the report below.
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
P_deadlock_free | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | true | 0.02 seconds |
Assertion | Const | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|---|
P_stuck_loc | l=0 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.02567235057637113 | 26.294 seconds |
P_stuck_loc | l=2 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.12585365828116296 | 26.273 seconds |
P_stuck_loc | l=4 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.0983769231859356 | 27.833 seconds |
P_stuck_loc | l=6 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.10511040848080475 | 20.205 seconds |
P_stuck_loc | l=8 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.13688082780817062 | 25.34 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
P_stuck_loc1 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 1.0 | 1.912 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
R_outofpower_moves | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=8 | 225784 | 499681 | 14.07523346286561 | 6.7 seconds |
R_outofpower_moves | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=12 | 374244 | 821573 | 19.952933464857594 | 13.303 seconds |
R_outofpower_moves | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=16 | 509108 | 1113721 | 25.793430152446405 | 18.859 seconds |
R_outofpower_moves | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 31.688489488064018 | 23.98 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
R_outofpower_deliveries | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=8 | 225784 | 499681 | 0.19302287268054588 | 7.162 seconds |
R_outofpower_deliveries | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=12 | 374244 | 821573 | 0.3210684624455483 | 9.804 seconds |
R_outofpower_deliveries | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=16 | 509108 | 1113721 | 0.4607625718075473 | 19.639 seconds |
R_outofpower_deliveries | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.6096518176087244 | 26.749 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
R_outofpower_deliveries1 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.6018022361186941 | 25.962 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
A_stuck | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | true | 145.887 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
P_stuck | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 1.0 | 2.165 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
A_infinite_delivery | deliverMOD::rp_ref0::chargeStep=2 | batteryCapacity=8 | 227704 | 503041 | false | 5.162 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
P_stuck_loc_0 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.02567235057637113 | 19.149 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
P_stuck_loc_1 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.10511040848080475 | 23.989 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
P_stuck_loc_2 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.12585365828116296 | 20.031 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
P_stuck_loc_3 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.13688082780817062 | 22.073 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
P_stuck_loc_4 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.0983769231859356 | 25.396 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
P_stuck_loc_5 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.14021160097961305 | 21.851 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
P_stuck_loc_6 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.10511040848080475 | 16.946 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
P_stuck_loc_7 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.1258536582811629 | 26.402 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
P_stuck_loc_8 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 0.13688082780817062 | 19.145 seconds |
Assertion | Const | Const | states: | transitions: | result: | checkTime: |
---|---|---|---|---|---|---|
P_stuck_loc_9 | deliverMOD::rp_ref0::chargeStep=4 | batteryCapacity=20 | 643972 | 1405869 | 1.0 | 1.336 seconds |
This case study shows how our RoboChart could be used to model the stochastic behaviour of a delivery robot controller that has a movement control, a battery control, and a task management. The support of hierarchical state machines in RoboChart entitles us to model the situation when the robot runs out of power and gets stuck in a nice way. Additionally, automatically generated PRISM model from the RoboChart model in RoboTool allows us to analyse the probabilistic behaviour of the robot using PRISM.
Department of Computer Science
Deramore Lane, University of York, Heslington, York, YO10 5GH, UK
Tel: 01904 325500
University of York legal statements