Creating and Verifying a ROS Node

Imandrabot

At AI, we've been working on an IML (Imandra Modelling Language) interface to ROS, allowing one to develop ROS nodes and use Imandra to verify their properties. In this notebook, we will go through creation and verification of a Robotic Operating System (ROS) node in Imandra. We will make a robot control node that controls the motion of a simple 2-wheeler bot:

Imandrabot

We'll create a controller that uses the laser scanner to avoid obstacles and drive around the scene. The Imandra ML code can be compiled in OCaml and plugged into the ROS system - the behaviour of the bot can be observed in the Gazebo simulator.

Then we'll illustrate how to use Imandra to formally verify various statements about the model and how to find bugs and corner cases by exploring the Imandra-generated counterexamples for false conjectures.

1. ROS message OCaml types

For our Imandra-ROS project we’ve processed all the standard ROS messages with our code generation tool creating a collection of strongly-typed IML/OCaml bindings for them. But, in order to keep this notebook self-contained we'll define the necessary messaging modules here.

First, we'll need to declare the message type that will control our robot. This is typically done with a Twist message from the geometry_msgs standard ROS package. We want to mimic ROS messaging nomenclauture as close as possible, so we'll create an OCaml/Imadra module with the same name as the package and will place the necessary type/message declaraions inside:

In [1]:
module Geometry_msgs = struct
  type vector3 = 
    { vector3_x : int
    ; vector3_y : int
    ; vector3_z : int
    }
  type twist = 
    { twist_linear  : vector3
    ; twist_angular : vector3
    }    
end
Out[1]:
module Geometry_msgs :
  sig
    type vector3 = { vector3_x : int; vector3_y : int; vector3_z : int; }
    type twist = { twist_linear : vector3; twist_angular : vector3; }
  end

You might have noticed that we've replaced floating point values for vector coordinates with integers. In this context, it is more straight-forward for Imandra to reason about integers, so we assume that there is a common factor of 100,000 multiplying all the incoming floating point values and divides all the outgoing integers. (That effectively makes our unit of measurement of length to be 10 micrometres).

Let's move on and declare the incoming messages:

  • LaserScan sensor input message from the sensor_msgs ROS package
  • and the Clock message from the Rosgraph_msg ROS package

We define the wrapping modules for both messages and declare their datatypes:

In [2]:
module Sensor_msgs = struct
  type laserScan = 
    { laserScan_range_min : int 
    ; laserScan_range_max : int 
    ; laserScan_ranges : int list 
    }
end
module Rosgraph_msgs = struct
  type time = 
    { seconds     : int
    ; nanoseconds : int
    }
  type clock = { clock : time }
end
Out[2]:
module Sensor_msgs :
  sig
    type laserScan = {
      laserScan_range_min : int;
      laserScan_range_max : int;
      laserScan_ranges : int list;
    }
  end
module Rosgraph_msgs :
  sig
    type time = { seconds : int; nanoseconds : int; }
    type clock = { clock : time; }
  end

Robotics OS middleware will communicate with our node via messages of these three types. The code that we'll write for of our node will represent the formal mathematical model of the controller algorithm - we can use Imandra to reason and verify various statements about the code. Since IML is valid OCaml, we'll leverage its compiler to create an executable from the verified IML code.

2. Creating a simple ROS Node model

We want to create some simple but non-trivial robot controller that makes our bot drive around avoiding the obstacles. The bot is going to drive forward until one of the laser scanner ranges becomes too low, meaning that we've gotten too close to some obstacle - in that case, we want the bot to stop and turn until the scanner tells us that the road ahead is clear. To make the model a bit more complicated, we'd like to implement the ability to choose the turning direction depending on the laser scanner ranges.

One might try to make a "naive" controller that doesn't have any memory about its previous states and observations - such a bot reacts to the currently observed scanner values and decides its actions based solely on that information. Such an approach will quickly lead to the bot being "stuck" in infinite oscillatory loops. E.g. here is a bot that decides which side to turn depending on the first value in the ranges array:

Imandrabot

To avoid this kind of oscillations we need the model to have some memory of its previous states. The idea is to introduce two modes of model's operation: driving forward and turning in one place. The bot is in the "driving" mode by default, but it can transition to the turning mode if it gets dangerously close to surrounding objects.

The turning direction is calculated using the direction of the minimum of the distances that the scanner returns. While the robot is turning in one place, it stores the minimal range that the scanner has detected at that location. If at some point the scanner detects a range that is lower than the stored one - the turning direction gets recalculated, and the minimal range gets updated.

2.1 State datatype

Working with Imandra we’ve adopted a standard way to construct formal models of message-driven systems. At the top of the model we have a single OCaml datatype that holds all the data needed to describe the system at a given moment, including incoming and outgoing messages. We call this record type state. Together with this state type we define a one_step transition state -> state function, which performs a single logically isolated step of the simulation and returns the new state after the transition.

As an example, consider an IML/OCaml type declaration for a simple ROS node that is able to accept rosgraph_msgs/Clock and sensor_msgs/LaserScan standard ROS messages. We also want the state to store three values:

  • the current mode of the bot -- whether we are driving forward or turning in a preferred direction
  • the latest minimal value of the ranges that the laser sensor returns
  • the preferred side for the robot to turn -- either clockwise (CW) or counter-clockwise (CCW)

Finally, we want the node to be able to send geometry_msgs/Twist ROS message depending on the stored min_range data:

In [3]:
type incoming_msg = 
  | Clock  of Rosgraph_msgs.clock
  | Sensor of Sensor_msgs.laserScan
  
type outgoing_msg =
  | Twist of Geometry_msgs.twist

type direction = CW | CCW 

type mode = Driving | Turning

type state =
  { mode : mode
  ; min_range : int option
  ; direction : direction option
  ; incoming  : incoming_msg option
  ; outgoing  : outgoing_msg option 
  }
Out[3]:
type incoming_msg =
    Clock of Rosgraph_msgs.clock
  | Sensor of Sensor_msgs.laserScan
type outgoing_msg = Twist of Geometry_msgs.twist
type direction = CW | CCW
type mode = Driving | Turning
type state = {
  mode : mode;
  min_range : int option;
  direction : direction option;
  incoming : incoming_msg option;
  outgoing : outgoing_msg option;
}

2.2 State transition one_step function

To implement our node, we'll need a function that scans through a list of values and returns the minimum value and its index. We'll make a generic function foldi that does an indexed version of the List.fold_right:

In [4]:
let rec foldi ~base ?(i=0) f l =
  match l with
  | [] -> base
  | x :: tail -> f i x ( foldi f ~base ~i:(i+1) tail )
Out[4]:
val foldi : base:'a -> ?i:Z.t -> (Z.t -> 'b -> 'a -> 'a) -> 'b list -> 'a =
  <fun>
termination proof

Termination proof

call `foldi base (Some ((if Is_a(Some, *opt*) then Option.get *opt* else 0) + 1)) f_2 (List.tl l)` from `foldi base *opt* f_2 l`
originalfoldi base *opt* f_2 l
subfoldi base (Some ((if Is_a(Some, *opt*) then Option.get *opt* else 0) + 1)) f_2 (List.tl l)
original ordinalOrdinal.Int (Ordinal.count l)
sub ordinalOrdinal.Int (Ordinal.count (List.tl l))
path[not (l = [])]
proof
detailed proof
ground_instances3
definitions0
inductions0
search_time
0.013s
details
Expand
smt_stats
num checks7
arith assert lower5
arith pivots3
rlimit count1821
mk clause3
datatype occurs check21
mk bool var50
arith assert upper5
datatype splits3
decisions7
arith add rows7
propagations2
conflicts7
arith fixed eqs4
datatype accessor ax5
arith conflicts1
datatype constructor ax8
num allocs1365196829
final checks6
added eqs33
del clause1
arith eq adapter3
memory16.080000
max memory18.750000
Expand
  • start[0.013s]
      not (l = []) && Ordinal.count l >= 0 && Ordinal.count (List.tl l) >= 0
      ==> List.tl l = []
          || Ordinal.Int (Ordinal.count (List.tl l)) Ordinal.<<
             Ordinal.Int (Ordinal.count l)
  • simplify
    into
    (not
     ((not (l = []) && Ordinal.count l >= 0) && Ordinal.count (List.tl l) >= 0)
     || List.tl l = [])
    || Ordinal.Int (Ordinal.count (List.tl l)) Ordinal.<<
       Ordinal.Int (Ordinal.count l)
    expansions
    []
    rewrite_steps
      forward_chaining
      • unroll
        expr
        (|Ordinal.<<_121| (|Ordinal.Int_112|
                            (|count_`ty_1 list`_2542| (|get.::.1_2520| …
        expansions
        • unroll
          expr
          (|count_`ty_1 list`_2542| (|get.::.1_2520| l_2531))
          expansions
          • unroll
            expr
            (|count_`ty_1 list`_2542| l_2531)
            expansions
            • unsat
              (let ((a!1 (= (|count_`ty_1 list`_2542| l_2531)
                            (+ 1 (|count_`ty_1 list`_2542| (|get.:…

            When accepting this function, Imandra constructs its "termination proof" - that means that Imandra managed to prove that recursive calls in this function will not end up in an infinite loop. Imandra proves such things using inductive reasoning and is able to prove further statements about other properties of such functions.

            In [5]:
            let get_min_range max lst =
              List.fold_right ~base:max
                (fun x a -> if x < a then x else a) lst
            
            Out[5]:
            val get_min_range : int -> int list -> int = <fun>
            

            On an incoming Clock tick we are simply sending out a Twist message which tells the robot to either move forward or turn, depending on the mode that it is currently in. We encode it by introducing the make_twist_message helper function and the process_clock_message : state -> state function.

            In [6]:
            let make_twist_message v omega=
              let open Geometry_msgs in
              let mkvector x y z =  { vector3_x = x; vector3_y = y; vector3_z = z   } in 
              Twist { twist_linear  = mkvector v 0 0 ; twist_angular = mkvector 0 0 omega }
            
            let process_clock_message state =
              match state.mode with 
              | Driving -> { state with outgoing = Some (make_twist_message 10000 0) } 
              | Turning -> begin
              match state.direction with 
                | None
                | Some ( CW ) -> { state with outgoing = Some (make_twist_message 0   10000) } 
                | Some (CCW ) -> { state with outgoing = Some (make_twist_message 0 (-10000))} 
              end
            
            Out[6]:
            val make_twist_message : int -> int -> outgoing_msg = <fun>
            val process_clock_message : state -> state = <fun>
            

            On incoming Scan message, we want to find the minimum of the received ranges and the index of that minimum in the list. Depending on the index, we decide in which direction to turn. To implement this, we create another helper function and the process_sensor_message one:

            In [7]:
            let get_min_and_direction msg =
              let max = msg.Sensor_msgs.laserScan_range_max in
              let lst = msg.Sensor_msgs.laserScan_ranges in
              let min_range = get_min_range max lst in
              let mini = foldi ~base:(max, 0)
                (fun i a b -> if a < fst b then (a,i) else b) in
              let _ , idx = mini lst in
              if idx < List.length lst / 2 then min_range, CW else min_range, CCW
            
            let process_sensor_message state min_range min_direction =
              let dirving_state = 
                { state with mode = Driving; min_range = None; direction = None } in
              let turning_state = 
                { state with 
                  mode      = Turning
                ; direction = Some min_direction
                ; min_range = Some min_range 
                } in  
              match state.mode , state.min_range with 
              | Driving , _    -> if min_range < 20000 then turning_state else dirving_state
              | Turning , None -> if min_range > 25000 then dirving_state else turning_state
              | Turning , Some old_range -> 
                if min_range > 25000 then dirving_state
                else if min_range > old_range then state else turning_state
            
            Out[7]:
            val get_min_and_direction : Sensor_msgs.laserScan -> int * direction = <fun>
            val process_sensor_message : state -> int -> direction -> state = <fun>
            

            With the help of these functions, we can create our one_step transition function, which just dispatches the messages to the appropriate helper function above.

            In [8]:
            let one_step state =
              match state.incoming with None -> state | Some in_msg ->
              let state = { state with incoming = None; outgoing = None } in
              match in_msg with 
              | Sensor laserScan -> 
                let min_range, min_direction = get_min_and_direction laserScan in
                process_sensor_message state min_range min_direction
              | Clock  _ -> process_clock_message state
            
            Out[8]:
            val one_step : state -> state = <fun>
            

            2.3 Running the model as a ROS node

            Now that we have an early model, let's compile it with our ROS node wrapper into an executable. Here is the model, controlling our "imandrabot" in the Gazebo simulation environment:

            Imandrabot

            3. Verifying the ROS node model

            Formal verification is the process of reasoning mathematically about the correctness of computer programs. We'll use Imandra to formally verify some properties of the ROS node model we've created.

            3.1 Verifying outgoing Twist message at Clock ticks

            Our model is designed in such a way that it updates its state parameters upon LaserScan messages and sends out Twist control messages in response to Clock messages. Let's verify a simple theorem that on every incoming Clock message, there is an outgoing Twist message.

            We can formally write this statement down as:

            $$ \forall s. IsClock(IncomingMessage(s)) \,\Rightarrow\, IsTwist(OutgoingMessage(OneStep(s))) $$

            eaning that for every state $s$, if the state contains an incoming message and this message is a Clock message, then the state's outgoing message is a Twist after we've called one_step on it.

            We can almost literally encode this formal expression as an Imandra theorem:

            In [9]:
            let is_clock msg = match msg with  Some ( Clock _ ) -> true | _ -> false ;;
            let is_twist msg = match msg with  Some ( Twist _ ) -> true | _ -> false ;;
            
            theorem clock_creates_outbound state =
              is_clock state.incoming ==> is_twist (one_step state).outgoing
            
            Out[9]:
            val is_clock : incoming_msg option -> bool = <fun>
            val is_twist : outgoing_msg option -> bool = <fun>
            val clock_creates_outbound : state -> bool = <fun>
            
            Proved
            proof
            ground_instances0
            definitions0
            inductions0
            search_time
            0.011s
            details
            Expand
            smt_stats
            num checks2
            arith assert lower1
            rlimit count2423
            mk clause36
            mk bool var207
            arith assert upper1
            datatype splits26
            decisions17
            propagations33
            conflicts10
            datatype accessor ax47
            datatype constructor ax33
            num allocs1413244003
            added eqs284
            memory16.890000
            max memory18.750000
            Expand
            • start[0.011s]
                (if Is_a(Clock, Option.get :var_0:.incoming)
                    && Is_a(Some, :var_0:.incoming)
                 then true else false)
                ==> (if Is_a(Twist,
                        Option.get
                        (if :var_0:.incoming = None then :var_0: else …).outgoing)
                        && Is_a(Some,
                           (if :var_0:.incoming = None then :var_0: else …).outgoing)
                     then true else false)
            • simplify

              into
              not
              (Is_a(Clock, Option.get :var_0:.incoming) && Is_a(Some, :var_0:.incoming))
              || Is_a(Twist,
                 Option.get (if :var_0:.incoming = None then :var_0: else …).outgoing)
                 && Is_a(Some, (if :var_0:.incoming = None then :var_0: else …).outgoing)
              expansions
              []
              rewrite_steps
                forward_chaining
                • unsat

                  (let ((a!1 (|Sensor_msgs.laserScan_ranges_2444|
                               (|get.Sensor.0_2714|
                                 (|g…

                One can see that Imandra says that it "Proved" the theorem, meaning that Imandra has formally checked that this property holds for all possible input states.

                3.2 Verifying that we never drive backwards

                As another example, let us check that, no matter what, the node will never send out a message with negative linear velocity.

                In [10]:
                let no_moving_back msg = 
                    let open Geometry_msgs in
                    match msg with None -> true 
                    | Some (Twist data) -> data.twist_linear.vector3_x >= 0
                  
                verify ( fun state -> no_moving_back (one_step state).outgoing  )
                
                Out[10]:
                val no_moving_back : outgoing_msg option -> bool = <fun>
                - : state -> bool = <fun>
                module CX : sig val state : state end
                
                Counterexample (after 3 steps, 0.020s):
                 let state =
                   {mode = Turning; min_range = (Some 2282); direction = None;
                    incoming = None;
                    outgoing =
                     (Some
                      (Twist
                         ({Geometry_msgs.twist_linear =
                            {Geometry_msgs.vector3_x = (-1); Geometry_msgs.vector3_y = 8;
                             Geometry_msgs.vector3_z = 9};
                           Geometry_msgs.twist_angular =
                            {Geometry_msgs.vector3_x = 10; Geometry_msgs.vector3_y = 11;
                             Geometry_msgs.vector3_z = 12}})))}
                
                Refuted
                proof attempt
                ground_instances3
                definitions0
                inductions0
                search_time
                0.020s
                details
                Expand
                smt_stats
                arith offset eqs2
                num checks7
                arith assert lower4
                arith pivots1
                rlimit count7405
                mk clause54
                datatype occurs check309
                mk bool var469
                arith assert upper12
                datatype splits46
                decisions251
                arith add rows1
                propagations236
                conflicts13
                datatype accessor ax78
                datatype constructor ax211
                num allocs1499422008
                final checks10
                added eqs1027
                del clause1
                arith eq adapter3
                memory17.900000
                max memory18.750000
                Expand
                • start[0.020s]
                    if (if :var_0:.incoming = None then :var_0:
                        else
                        if Is_a(Sensor, Option.get :var_0:.incoming)
                        then if ….mode = Driving then … else …
                        else if ….mode = Driving then … else …).outgoing
                       = None
                    then true
                    else
                      (Destruct(Twist, 0, …)).Geometry_msgs.twist_linear.Geometry_msgs.vector3_x
                      >= 0
                • simplify

                  into
                  (if :var_0:.incoming = None then :var_0:
                   else
                   if Is_a(Sensor, Option.get :var_0:.incoming)
                   then if :var_0:.mode = Driving then … else …
                   else if :var_0:.mode = Driving then … else …).outgoing
                  = None
                  || (Destruct(Twist, 0,
                               Option.get
                               (if :var_0:.incoming = None then :var_0:
                                else
                                if Is_a(Sensor, Option.get :var_0:.incoming)
                                then if :var_0:.mode = Driving then … else …
                                else if :var_0:.mode = Driving then … else …).outgoing)).Geometry_msgs.twist_linear.Geometry_msgs.vector3_x
                     >= 0
                  expansions
                  []
                  rewrite_steps
                    forward_chaining
                    • unroll
                      expr
                      (let ((a!1 (|Sensor_msgs.laserScan_range_max_2443|
                                   (|get.Sensor.0_2783|
                                     …
                      expansions
                      • unroll
                        expr
                        (let ((a!1 (|Sensor_msgs.laserScan_range_max_2443|
                                     (|get.Sensor.0_2783|
                                       …
                        expansions
                        • unroll
                          expr
                          (let ((a!1 (|Sensor_msgs.laserScan_ranges_2444|
                                       (|get.Sensor.0_2783|
                                         (|g…
                          expansions
                          • Sat (Some let state = {mode = Turning; min_range = (Some 2282); direction = None; incoming = None; outgoing = (Some (Twist ({Geometry_msgs.twist_linear = {Geometry_msgs.vector3_x = (-1); Geometry_msgs.vector3_y = 8; Geometry_msgs.vector3_z = 9}; Geometry_msgs.twist_angular = {Geometry_msgs.vector3_x = 10; Geometry_msgs.vector3_y = 11; Geometry_msgs.vector3_z = 12}})))} )

                          We have failed to prove the statement and Imandra have created a counterexample CX module for us. This module contains concrete values for the parameters of the verified statement, that violate the statement's condition. Let's examine the value of CX.state:

                          In [11]:
                          CX.state
                          
                          Out[11]:
                          - : state =
                          {mode = Turning; min_range = Some 2282; direction = None; incoming = None;
                           outgoing =
                            Some
                             (Twist
                               {Geometry_msgs.twist_linear =
                                 {Geometry_msgs.vector3_x = -1; vector3_y = 8; vector3_z = 9};
                                twist_angular =
                                 {Geometry_msgs.vector3_x = 10; vector3_y = 11; vector3_z = 12}})}
                          

                          The counterexample state produced by imandra has the incoming message set to None and the outgoing message set to a Twist message with negative linear.x. Our one_step function keeps the state unchanged if the incoming message is empty.

                          We can either consider this behavior as a bug and change our one_step implementation; or we can consider this a normal behavior and amend our theorem, adding the non-empty incoming message as an extra premise of the theorem:

                          In [12]:
                          theorem never_goes_back state = 
                            state.incoming <> None
                            ==>
                            no_moving_back (one_step state).outgoing
                          
                          Out[12]:
                          val never_goes_back : state -> bool = <fun>
                          
                          Proved
                          proof
                          ground_instances0
                          definitions0
                          inductions0
                          search_time
                          0.013s
                          details
                          Expand
                          smt_stats
                          num checks2
                          arith assert lower2
                          rlimit count3200
                          mk clause45
                          mk bool var264
                          arith assert upper9
                          datatype splits26
                          decisions48
                          propagations154
                          conflicts21
                          datatype accessor ax56
                          minimized lits6
                          arith assert diseq2
                          datatype constructor ax69
                          num allocs1550152666
                          added eqs488
                          arith eq adapter4
                          memory21.370000
                          max memory21.370000
                          Expand
                          • start[0.013s]
                              not (:var_0:.incoming = None)
                              ==> (if (if :var_0:.incoming = None then :var_0:
                                       else
                                       if Is_a(Sensor, Option.get :var_0:.incoming)
                                       then if ….mode = Driving then … else …
                                       else if ….mode = Driving then … else …).outgoing
                                      = None
                                   then true
                                   else
                                     (Destruct(Twist, 0, …)).Geometry_msgs.twist_linear.Geometry_msgs.vector3_x
                                     >= 0)
                          • simplify

                            into
                            (:var_0:.incoming = None
                             || (if :var_0:.incoming = None then :var_0:
                                 else
                                 if Is_a(Sensor, Option.get :var_0:.incoming)
                                 then if :var_0:.mode = Driving then … else …
                                 else if :var_0:.mode = Driving then … else …).outgoing
                                = None)
                            || (Destruct(Twist, 0,
                                         Option.get
                                         (if :var_0:.incoming = None then :var_0:
                                          else
                                          if Is_a(Sensor, Option.get :var_0:.incoming)
                                          then if :var_0:.mode = Driving then … else …
                                          else if :var_0:.mode = Driving then … else …).outgoing)).Geometry_msgs.twist_linear.Geometry_msgs.vector3_x
                               >= 0
                            expansions
                            []
                            rewrite_steps
                              forward_chaining
                              • unsat

                                (let ((a!1 (Twist_2472 (|rec_mk.Geometry_msgs.twist_2926|
                                                         (|rec_mk.Geometry…

                              We've proven that the model never creates negative linear speed in response to any incoming message - alternatively we can set state.outgoing = None as a premise, proving that an empty outgoing message is never filled with a Twist with negative velocity:

                              In [13]:
                              theorem never_goes_back_alt state = 
                                state.outgoing = None
                                ==>
                                no_moving_back (one_step state).outgoing
                              
                              Out[13]:
                              val never_goes_back_alt : state -> bool = <fun>
                              
                              Proved
                              proof
                              ground_instances0
                              definitions0
                              inductions0
                              search_time
                              0.013s
                              details
                              Expand
                              smt_stats
                              num checks2
                              arith assert lower2
                              rlimit count3451
                              mk clause48
                              mk bool var282
                              arith assert upper12
                              datatype splits26
                              decisions59
                              propagations172
                              conflicts23
                              datatype accessor ax56
                              minimized lits6
                              arith assert diseq2
                              datatype constructor ax85
                              num allocs1625015330
                              added eqs555
                              del clause8
                              arith eq adapter4
                              memory26.010000
                              max memory26.010000
                              Expand
                              • start[0.013s]
                                  :var_0:.outgoing = None
                                  ==> (if (if :var_0:.incoming = None then :var_0:
                                           else
                                           if Is_a(Sensor, Option.get :var_0:.incoming)
                                           then if ….mode = Driving then … else …
                                           else if ….mode = Driving then … else …).outgoing
                                          = None
                                       then true
                                       else
                                         (Destruct(Twist, 0, …)).Geometry_msgs.twist_linear.Geometry_msgs.vector3_x
                                         >= 0)
                              • simplify

                                into
                                (not (:var_0:.outgoing = None)
                                 || (if :var_0:.incoming = None then :var_0:
                                     else
                                     if Is_a(Sensor, Option.get :var_0:.incoming)
                                     then if :var_0:.mode = Driving then … else …
                                     else if :var_0:.mode = Driving then … else …).outgoing
                                    = None)
                                || (Destruct(Twist, 0,
                                             Option.get
                                             (if :var_0:.incoming = None then :var_0:
                                              else
                                              if Is_a(Sensor, Option.get :var_0:.incoming)
                                              then if :var_0:.mode = Driving then … else …
                                              else if :var_0:.mode = Driving then … else …).outgoing)).Geometry_msgs.twist_linear.Geometry_msgs.vector3_x
                                   >= 0
                                expansions
                                []
                                rewrite_steps
                                  forward_chaining
                                  • unsat

                                    (let ((a!1 (Twist_2472 (|rec_mk.Geometry_msgs.twist_3063|
                                                             (|rec_mk.Geometry…

                                  4. Inductive proofs. Stopping near objects.

                                  As a final formal verification goal, we want to be able to prove that the robot stops and starts turning if one of the values in the scanner ranges is lower than 0.2 meters. In general, reasoning about variable-sized lists requires inductive proofs - and these might require proving some lemmas to guide Imandra to the proof. So, we will first try to prove a simpler version of the theorem - if all the ranges in the incoming laser scan message are less than 0.2 meters, then we definitely transition to the Turning state. We'll try to encode our theorem using List.for_all standard function:

                                  In [14]:
                                  verify ( fun state ->
                                    let open Sensor_msgs in
                                    match state.incoming with None | Some (Clock _ ) -> true 
                                    | Some ( Sensor data ) ->
                                    (  List.for_all (fun x -> x < 20000) data.laserScan_ranges    
                                    ) ==> (one_step state).mode = Turning
                                  )
                                  
                                  Out[14]:
                                  - : state -> bool = <fun>
                                  module CX : sig val state : state end
                                  
                                  Counterexample (after 4 steps, 0.023s):
                                   let state =
                                     {mode = Turning; min_range = (Some 7719); direction = None;
                                      incoming =
                                       (Some
                                        (Sensor
                                           ({Sensor_msgs.laserScan_range_min = 3;
                                             Sensor_msgs.laserScan_range_max = 25001;
                                             Sensor_msgs.laserScan_ranges = []})));
                                      outgoing = None}
                                  
                                  Refuted
                                  proof attempt
                                  ground_instances4
                                  definitions0
                                  inductions0
                                  search_time
                                  0.023s
                                  details
                                  Expand
                                  smt_stats
                                  arith offset eqs3
                                  num checks9
                                  arith assert lower26
                                  arith pivots15
                                  rlimit count8187
                                  mk clause67
                                  datatype occurs check439
                                  mk bool var468
                                  arith assert upper22
                                  datatype splits54
                                  decisions250
                                  arith add rows13
                                  arith bound prop1
                                  propagations198
                                  conflicts18
                                  arith fixed eqs5
                                  datatype accessor ax62
                                  minimized lits1
                                  datatype constructor ax209
                                  num allocs1710270881
                                  final checks16
                                  added eqs1013
                                  del clause10
                                  arith eq adapter9
                                  memory30.450000
                                  max memory30.450000
                                  Expand
                                  • start[0.023s]
                                      if :var_0:.incoming = None
                                         || Is_a(Some, :var_0:.incoming)
                                            && Is_a(Clock, Option.get :var_0:.incoming)
                                      then true
                                      else
                                        List.for_all (fun x -> x < 20000)
                                        (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges
                                        ==> (if :var_0:.incoming = None then :var_0:
                                             else if Is_a(Sensor, Option.get :var_0:.incoming) then … else …).mode
                                            = Turning
                                  • simplify

                                    into
                                    ((:var_0:.incoming = None
                                      || Is_a(Some, :var_0:.incoming) && Is_a(Clock, Option.get :var_0:.incoming))
                                     || not
                                        (List.for_all (fun x -> x < 20000)
                                         (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges))
                                    || (if :var_0:.incoming = None then :var_0:
                                        else
                                        if Is_a(Sensor, Option.get :var_0:.incoming)
                                        then if :var_0:.mode = Driving then … else …
                                        else if :var_0:.mode = Driving then … else …).mode
                                       = Turning
                                    expansions
                                    []
                                    rewrite_steps
                                      forward_chaining
                                      • unroll
                                        expr
                                        (let ((a!1 (|Sensor_msgs.laserScan_range_max_2443|
                                                     (|get.Sensor.0_3156|
                                                       …
                                        expansions
                                        • unroll
                                          expr
                                          (let ((a!1 (|Sensor_msgs.laserScan_range_max_2443|
                                                       (|get.Sensor.0_3156|
                                                         …
                                          expansions
                                          • unroll
                                            expr
                                            (let ((a!1 (|Sensor_msgs.laserScan_ranges_2444|
                                                         (|get.Sensor.0_3156|
                                                           (|g…
                                            expansions
                                            • unroll
                                              expr
                                              (let ((a!1 (|Sensor_msgs.laserScan_ranges_2444|
                                                           (|get.Sensor.0_3156|
                                                             (|g…
                                              expansions
                                              • Sat (Some let state = {mode = Turning; min_range = (Some 7719); direction = None; incoming = (Some (Sensor ({Sensor_msgs.laserScan_range_min = 3; Sensor_msgs.laserScan_range_max = 25001; Sensor_msgs.laserScan_ranges = []}))); outgoing = None} )

                                              We have failed to prove the statement and Imandra has created a counterexample CX module for us. Examining the counterexample state we notice that the incoming laserScan_ranges list is empty.

                                              In [15]:
                                              CX.state
                                              
                                              Out[15]:
                                              - : state =
                                              {mode = Turning; min_range = Some 7719; direction = None;
                                               incoming =
                                                Some
                                                 (Sensor
                                                   {Sensor_msgs.laserScan_range_min = 3; laserScan_range_max = 25001;
                                                    laserScan_ranges = []});
                                               outgoing = None}
                                              

                                              Adding the extra requirement that the list is not [], we successfully verify the statement:

                                              In [16]:
                                              theorem stopping_if_for_all state =
                                                let open Sensor_msgs in
                                                match state.incoming with None | Some (Clock _ ) -> true 
                                                | Some ( Sensor data ) ->
                                                (  data.laserScan_ranges <> []
                                                && List.for_all (fun x -> x < 20000) data.laserScan_ranges    
                                                ) ==> (one_step state).mode = Turning
                                              
                                              Out[16]:
                                              val stopping_if_for_all : state -> bool = <fun>
                                              
                                              Proved
                                              proof
                                              ground_instances4
                                              definitions0
                                              inductions0
                                              search_time
                                              0.022s
                                              details
                                              Expand
                                              smt_stats
                                              num checks10
                                              arith assert lower52
                                              arith pivots15
                                              rlimit count9983
                                              mk clause78
                                              datatype occurs check359
                                              mk bool var571
                                              arith assert upper43
                                              datatype splits56
                                              decisions365
                                              arith add rows20
                                              arith bound prop2
                                              propagations317
                                              conflicts31
                                              arith fixed eqs9
                                              datatype accessor ax56
                                              minimized lits2
                                              arith conflicts3
                                              arith assert diseq27
                                              datatype constructor ax298
                                              num allocs1782006684
                                              final checks13
                                              added eqs1430
                                              del clause36
                                              arith eq adapter27
                                              memory33.960000
                                              max memory33.960000
                                              Expand
                                              • start[0.022s]
                                                  if :var_0:.incoming = None
                                                     || Is_a(Some, :var_0:.incoming)
                                                        && Is_a(Clock, Option.get :var_0:.incoming)
                                                  then true
                                                  else
                                                    not
                                                    ((Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges
                                                     = [])
                                                    && List.for_all (fun x -> x < 20000)
                                                       (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges
                                                    ==> (if :var_0:.incoming = None then :var_0:
                                                         else if Is_a(Sensor, Option.get :var_0:.incoming) then … else …).mode
                                                        = Turning
                                              • simplify

                                                into
                                                ((:var_0:.incoming = None
                                                  || Is_a(Some, :var_0:.incoming) && Is_a(Clock, Option.get :var_0:.incoming))
                                                 || not
                                                    (not
                                                     ((Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges
                                                      = [])
                                                     && List.for_all (fun x -> x < 20000)
                                                        (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges))
                                                || (if :var_0:.incoming = None then :var_0:
                                                    else
                                                    if Is_a(Sensor, Option.get :var_0:.incoming)
                                                    then if :var_0:.mode = Driving then … else …
                                                    else if :var_0:.mode = Driving then … else …).mode
                                                   = Turning
                                                expansions
                                                []
                                                rewrite_steps
                                                  forward_chaining
                                                  • unroll
                                                    expr
                                                    (let ((a!1 (|Sensor_msgs.laserScan_range_max_2443|
                                                                 (|get.Sensor.0_3305|
                                                                   …
                                                    expansions
                                                    • unroll
                                                      expr
                                                      (let ((a!1 (|Sensor_msgs.laserScan_range_max_2443|
                                                                   (|get.Sensor.0_3305|
                                                                     …
                                                      expansions
                                                      • unroll
                                                        expr
                                                        (let ((a!1 (|Sensor_msgs.laserScan_ranges_2444|
                                                                     (|get.Sensor.0_3305|
                                                                       (|g…
                                                        expansions
                                                        • unroll
                                                          expr
                                                          (let ((a!1 (|Sensor_msgs.laserScan_ranges_2444|
                                                                       (|get.Sensor.0_3305|
                                                                         (|g…
                                                          expansions
                                                          • unsat

                                                            (let ((a!1 (|Sensor_msgs.laserScan_range_max_2443|
                                                                         (|get.Sensor.0_3305|
                                                                           …

                                                          Imandra successfully proves the stopping_if_for_all theorem, but our ultimate goal is to prove the theorem when some of the values in laserScan_ranges are less than the cutoff. If we simply try to replace the List.for_all with List.exists, Imandra will fail to either prove or disprove the theorem. The inductive structure of this proof is too complex for Imandra to figure out automatically without any hints from the user. We need to help it with the overall logic of the proof. To do that we will break this final theorem into several smaller steps, making a rough "sketch" of the inductive proof we want and and ask Imandra to fill in the gaps.

                                                          As a first step, we extract the anonymous threshold function and prove a lemma that if the get_min_range function returns a value satisfying the threshold, then the conclusion about the one_step function holds:

                                                          In [17]:
                                                          let under_threshold x = x < 20000
                                                          
                                                          lemma lemma1 state =
                                                            let open Sensor_msgs in
                                                            match state.incoming with None | Some (Clock _ ) -> true 
                                                            | Some ( Sensor data ) ->
                                                            (  data.laserScan_ranges <> []
                                                            && under_threshold (get_min_range data.laserScan_range_max data.laserScan_ranges)
                                                            ) ==> (one_step state).mode = Turning
                                                          
                                                          Out[17]:
                                                          val under_threshold : int -> bool = <fun>
                                                          val lemma1 : state -> bool = <fun>
                                                          
                                                          Proved
                                                          proof
                                                          ground_instances0
                                                          definitions0
                                                          inductions0
                                                          search_time
                                                          0.013s
                                                          details
                                                          Expand
                                                          smt_stats
                                                          num checks2
                                                          arith assert lower5
                                                          arith pivots2
                                                          rlimit count2970
                                                          mk clause42
                                                          mk bool var240
                                                          arith assert upper8
                                                          datatype splits26
                                                          decisions43
                                                          arith add rows1
                                                          arith bound prop1
                                                          propagations78
                                                          conflicts12
                                                          arith fixed eqs2
                                                          datatype accessor ax48
                                                          minimized lits1
                                                          arith assert diseq1
                                                          datatype constructor ax61
                                                          num allocs1874647944
                                                          added eqs340
                                                          del clause15
                                                          arith eq adapter4
                                                          memory38.340000
                                                          max memory38.340000
                                                          Expand
                                                          • start[0.013s]
                                                              if :var_0:.incoming = None
                                                                 || Is_a(Some, :var_0:.incoming)
                                                                    && Is_a(Clock, Option.get :var_0:.incoming)
                                                              then true
                                                              else
                                                                not
                                                                ((Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges
                                                                 = [])
                                                                && List.fold_right (fun x a -> if x < a then x else a)
                                                                   (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_range_max
                                                                   (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges
                                                                   < 20000
                                                                ==> (if :var_0:.incoming = None then :var_0:
                                                                     else if Is_a(Sensor, Option.get :var_0:.incoming) then … else …).mode
                                                                    = Turning
                                                          • simplify

                                                            into
                                                            ((:var_0:.incoming = None
                                                              || Is_a(Some, :var_0:.incoming) && Is_a(Clock, Option.get :var_0:.incoming))
                                                             || not
                                                                (not
                                                                 ((Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges
                                                                  = [])
                                                                 && not
                                                                    (20000 <=
                                                                     List.fold_right (fun x a -> if x < a then x else a)
                                                                     (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_range_max
                                                                     (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges)))
                                                            || (if :var_0:.incoming = None then :var_0:
                                                                else
                                                                if Is_a(Sensor, Option.get :var_0:.incoming)
                                                                then if :var_0:.mode = Driving then … else …
                                                                else if :var_0:.mode = Driving then … else …).mode
                                                               = Turning
                                                            expansions
                                                            []
                                                            rewrite_steps
                                                              forward_chaining
                                                              • unsat

                                                                (let ((a!1 (|Sensor_msgs.laserScan_ranges_2444|
                                                                             (|get.Sensor.0_3463|
                                                                               (|g…

                                                              Next, we prove a "bridge" lemma that translates between the get_min_range concept and the List.exists concept for the under_threshold function. Then, we [@@apply] the two lemmas above to prove our final theorem with the List.exists condition: these proofs require induction - to tell Imandra to use induction one should add the [@@induct] attribute to the theorem declaration:

                                                              In [18]:
                                                              lemma bridge max lst =
                                                                List.exists under_threshold lst ==> under_threshold (get_min_range max lst)
                                                                [@@induct]
                                                              
                                                              theorem stopping_if_exists state =
                                                                let open Sensor_msgs in
                                                                match state.incoming with None | Some (Clock _ ) -> true 
                                                                | Some ( Sensor data ) ->
                                                                (  data.laserScan_ranges <> []
                                                                && List.exists under_threshold data.laserScan_ranges
                                                                ) ==> (one_step state).mode = Turning
                                                              [@@apply lemma1 state]
                                                              [@@apply bridge
                                                                  (match state.incoming with Some (Sensor data) -> data.laserScan_range_max | _ -> 0)
                                                                  (match state.incoming with Some (Sensor data) -> data.laserScan_ranges | _ -> []) ]
                                                              [@@induct]
                                                              
                                                              Out[18]:
                                                              val bridge : int -> int list -> bool = <fun>
                                                              Goal:
                                                              
                                                              List.exists under_threshold lst ==> under_threshold (get_min_range max lst).
                                                              
                                                              1 nontautological subgoal.
                                                              
                                                              Subgoal 1:
                                                              
                                                               H0. List.exists under_threshold lst
                                                               H1. 20000 <= List.fold_right (fun x a -> if x < a then x else a) max lst
                                                              |---------------------------------------------------------------------------
                                                               false
                                                              
                                                              Verified up to bound 10 (after 0.025s).
                                                              
                                                              Must try induction.
                                                              
                                                              The recursive terms in the conjecture suggest 2 inductions.
                                                              Subsumption and merging reduces this to 1.
                                                              
                                                              We shall induct according to a scheme derived from List.fold_right.
                                                              
                                                              Induction scheme:
                                                              
                                                               (lst = []
                                                                && not
                                                                   (not
                                                                    (List.hd lst <
                                                                     List.fold_right (fun x a -> if x < a then x else a) max (List.tl lst))
                                                                    && not (lst = []))
                                                                ==> φ lst max)
                                                               && (not (lst = [])
                                                                   && not
                                                                      (List.hd lst <
                                                                       List.fold_right (fun x a -> if x < a then x else a) max
                                                                       (List.tl lst))
                                                                      && φ (List.tl lst) max
                                                                   ==> φ lst max)
                                                                  && (not (lst = []) && φ (List.tl lst) max ==> φ lst max).
                                                              
                                                              3 nontautological subgoals.
                                                              
                                                              Subgoal 1.3:
                                                              
                                                               H0. lst = []
                                                               H1. not
                                                                   (List.fold_right (fun x a -> if x < a then x else a) max (List.tl lst)
                                                                    <= List.hd lst && not (lst = []))
                                                               H2. List.exists under_threshold lst
                                                               H3. 20000 <= List.fold_right (fun x a -> if x < a then x else a) max lst
                                                              |---------------------------------------------------------------------------
                                                               false
                                                              
                                                              But simplification reduces this to true, using the definition of List.exists.
                                                              
                                                              Subgoal 1.2:
                                                              
                                                               H0. not (lst = [])
                                                               H1. List.fold_right (fun x a -> if x < a then x else a) max (List.tl lst) <=
                                                                   List.hd lst
                                                               H2. not (List.exists under_threshold (List.tl lst))
                                                                   || not
                                                                      (20000 <=
                                                                       List.fold_right (fun x a -> if x < a then x else a) max
                                                                       (List.tl lst))
                                                               H3. List.exists under_threshold lst
                                                               H4. 20000 <= List.fold_right (fun x a -> if x < a then x else a) max lst
                                                              |---------------------------------------------------------------------------
                                                               false
                                                              
                                                              But simplification reduces this to true, using the definitions of List.exists
                                                              and List.fold_right.
                                                              
                                                              Subgoal 1.1:
                                                              
                                                               H0. not (lst = [])
                                                               H1. not (List.exists under_threshold (List.tl lst))
                                                                   || not
                                                                      (20000 <=
                                                                       List.fold_right (fun x a -> if x < a then x else a) max
                                                                       (List.tl lst))
                                                               H2. List.exists under_threshold lst
                                                               H3. 20000 <= List.fold_right (fun x a -> if x < a then x else a) max lst
                                                              |---------------------------------------------------------------------------
                                                               false
                                                              
                                                              But simplification reduces this to true, using the definitions of List.exists
                                                              and List.fold_right.
                                                              
                                                              val stopping_if_exists : state -> bool = <fun>
                                                              Goal:
                                                              
                                                              if state.incoming = None
                                                                 || Is_a(Some, state.incoming) && Is_a(Clock, Option.get state.incoming)
                                                              then true
                                                              else
                                                                let (data : Sensor_msgs.laserScan)
                                                                    = Destruct(Sensor, 0, Option.get state.incoming)
                                                                in
                                                                data.Sensor_msgs.laserScan_ranges <> []
                                                                && List.exists under_threshold data.Sensor_msgs.laserScan_ranges
                                                                ==> (one_step state).mode = Turning.
                                                              
                                                              A hint has been given, resulting in the following augmented conjecture:
                                                              
                                                              Goal':
                                                              
                                                              (if state.incoming = None
                                                                  || Is_a(Some, state.incoming) && Is_a(Clock, Option.get state.incoming)
                                                               then true
                                                               else
                                                                 (not
                                                                  ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                   = [])
                                                                  && List.fold_right (fun x a -> if x < a then x else a)
                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                     < 20000
                                                                  ==> (if state.incoming = None then state
                                                                       else
                                                                       if Is_a(Sensor, Option.get state.incoming)
                                                                       then
                                                                         if state.mode = Driving
                                                                         then
                                                                           if (if (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                  <
                                                                                  (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)).0
                                                                              < 20000
                                                                           then
                                                                             {mode = Turning;
                                                                              min_range =
                                                                              Some
                                                                              (if (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                  <
                                                                                  (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)).0;
                                                                              direction =
                                                                              Some
                                                                              (if (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                  <
                                                                                  (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)).1;
                                                                              incoming = None; outgoing = None}
                                                                           else
                                                                             {mode = Driving; min_range = None; direction = None;
                                                                              incoming = None; outgoing = None}
                                                                         else
                                                                         if state.min_range = None && state.mode = Turning
                                                                         then
                                                                           if (if (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                  <
                                                                                  (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)).0
                                                                              > 25000
                                                                           then
                                                                             {mode = Driving; min_range = None; direction = None;
                                                                              incoming = None; outgoing = None}
                                                                           else
                                                                             {mode = Turning;
                                                                              min_range =
                                                                              Some
                                                                              (if (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                  <
                                                                                  (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)).0;
                                                                              direction =
                                                                              Some
                                                                              (if (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                  <
                                                                                  (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)).1;
                                                                              incoming = None; outgoing = None}
                                                                         else
                                                                         if (if (foldi
                                                                                 ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                  0)
                                                                                 None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                 (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                <
                                                                                (List.length
                                                                                 (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                 / 2)
                                                                             then
                                                                               (List.fold_right (fun x a -> if x < a then x else a)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                CW)
                                                                             else
                                                                               (List.fold_right (fun x a -> if x < a then x else a)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                CCW)).0
                                                                            > 25000
                                                                         then
                                                                           {mode = Driving; min_range = None; direction = None;
                                                                            incoming = None; outgoing = None}
                                                                         else
                                                                         if (if (foldi
                                                                                 ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                  0)
                                                                                 None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                 (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                <
                                                                                (List.length
                                                                                 (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                 / 2)
                                                                             then
                                                                               (List.fold_right (fun x a -> if x < a then x else a)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                CW)
                                                                             else
                                                                               (List.fold_right (fun x a -> if x < a then x else a)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                CCW)).0
                                                                            > Option.get state.min_range
                                                                         then
                                                                           {mode = state.mode; min_range = state.min_range;
                                                                            direction = state.direction; incoming = None; outgoing = None}
                                                                         else
                                                                           {mode = Turning;
                                                                            min_range =
                                                                            Some
                                                                            (if (foldi
                                                                                 ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                  0)
                                                                                 None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                 (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                <
                                                                                (List.length
                                                                                 (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                 / 2)
                                                                             then
                                                                               (List.fold_right (fun x a -> if x < a then x else a)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                CW)
                                                                             else
                                                                               (List.fold_right (fun x a -> if x < a then x else a)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                CCW)).0;
                                                                            direction =
                                                                            Some
                                                                            (if (foldi
                                                                                 ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                  0)
                                                                                 None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                 (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                <
                                                                                (List.length
                                                                                 (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                 / 2)
                                                                             then
                                                                               (List.fold_right (fun x a -> if x < a then x else a)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                CW)
                                                                             else
                                                                               (List.fold_right (fun x a -> if x < a then x else a)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                CCW)).1;
                                                                            incoming = None; outgoing = None}
                                                                       else
                                                                       if state.mode = Driving
                                                                       then
                                                                         {mode = state.mode; min_range = state.min_range;
                                                                          direction = state.direction; incoming = None;
                                                                          outgoing =
                                                                          Some
                                                                          (Twist
                                                                           {Geometry_msgs.twist_linear =
                                                                            {Geometry_msgs.vector3_x = 10000; Geometry_msgs.vector3_y = 0;
                                                                             Geometry_msgs.vector3_z = 0};
                                                                            Geometry_msgs.twist_angular =
                                                                            {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                             Geometry_msgs.vector3_z = 0}})}
                                                                       else
                                                                       if state.direction = None
                                                                          || Is_a(Some, state.direction) && Option.get state.direction = CW
                                                                       then
                                                                         {mode = state.mode; min_range = state.min_range;
                                                                          direction = state.direction; incoming = None;
                                                                          outgoing =
                                                                          Some
                                                                          (Twist
                                                                           {Geometry_msgs.twist_linear =
                                                                            {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                             Geometry_msgs.vector3_z = 0};
                                                                            Geometry_msgs.twist_angular =
                                                                            {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                             Geometry_msgs.vector3_z = 10000}})}
                                                                       else
                                                                         {mode = state.mode; min_range = state.min_range;
                                                                          direction = state.direction; incoming = None;
                                                                          outgoing =
                                                                          Some
                                                                          (Twist
                                                                           {Geometry_msgs.twist_linear =
                                                                            {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                             Geometry_msgs.vector3_z = 0};
                                                                            Geometry_msgs.twist_angular =
                                                                            {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                             Geometry_msgs.vector3_z = -10000}})}).mode
                                                                      = Turning))
                                                              && (List.exists under_threshold
                                                                  (if Is_a(Sensor, Option.get state.incoming) && Is_a(Some, state.incoming)
                                                                   then
                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                   else [])
                                                                  ==> List.fold_right (fun x a -> if x < a then x else a)
                                                                      (if Is_a(Sensor, Option.get state.incoming)
                                                                          && Is_a(Some, state.incoming)
                                                                       then
                                                                         (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                       else 0)
                                                                      (if Is_a(Sensor, Option.get state.incoming)
                                                                          && Is_a(Some, state.incoming)
                                                                       then
                                                                         (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                       else [])
                                                                      < 20000)
                                                              ==> (if state.incoming = None
                                                                      || Is_a(Some, state.incoming)
                                                                         && Is_a(Clock, Option.get state.incoming)
                                                                   then true
                                                                   else
                                                                     not
                                                                     ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                      = [])
                                                                     && List.exists under_threshold
                                                                        (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                     ==> (if state.incoming = None then state
                                                                          else
                                                                          if Is_a(Sensor, Option.get state.incoming)
                                                                          then
                                                                            if state.mode = Driving
                                                                            then
                                                                              if (if (foldi
                                                                                      ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                       0)
                                                                                      None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                      (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                     <
                                                                                     (List.length
                                                                                      (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                      / 2)
                                                                                  then
                                                                                    (List.fold_right (fun x a -> if x < a then x else a)
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                     CW)
                                                                                  else
                                                                                    (List.fold_right (fun x a -> if x < a then x else a)
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                     CCW)).0
                                                                                 < 20000
                                                                              then
                                                                                {mode = Turning;
                                                                                 min_range =
                                                                                 Some
                                                                                 (if (foldi
                                                                                      ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                       0)
                                                                                      None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                      (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                     <
                                                                                     (List.length
                                                                                      (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                      / 2)
                                                                                  then
                                                                                    (List.fold_right (fun x a -> if x < a then x else a)
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                     CW)
                                                                                  else
                                                                                    (List.fold_right (fun x a -> if x < a then x else a)
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                     CCW)).0;
                                                                                 direction =
                                                                                 Some
                                                                                 (if (foldi
                                                                                      ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                       0)
                                                                                      None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                      (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                     <
                                                                                     (List.length
                                                                                      (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                      / 2)
                                                                                  then
                                                                                    (List.fold_right (fun x a -> if x < a then x else a)
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                     CW)
                                                                                  else
                                                                                    (List.fold_right (fun x a -> if x < a then x else a)
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                     CCW)).1;
                                                                                 incoming = None; outgoing = None}
                                                                              else
                                                                                {mode = Driving; min_range = None; direction = None;
                                                                                 incoming = None; outgoing = None}
                                                                            else
                                                                            if state.min_range = None && state.mode = Turning
                                                                            then
                                                                              if (if (foldi
                                                                                      ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                       0)
                                                                                      None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                      (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                     <
                                                                                     (List.length
                                                                                      (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                      / 2)
                                                                                  then
                                                                                    (List.fold_right (fun x a -> if x < a then x else a)
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                     CW)
                                                                                  else
                                                                                    (List.fold_right (fun x a -> if x < a then x else a)
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                     CCW)).0
                                                                                 > 25000
                                                                              then
                                                                                {mode = Driving; min_range = None; direction = None;
                                                                                 incoming = None; outgoing = None}
                                                                              else
                                                                                {mode = Turning;
                                                                                 min_range =
                                                                                 Some
                                                                                 (if (foldi
                                                                                      ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                       0)
                                                                                      None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                      (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                     <
                                                                                     (List.length
                                                                                      (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                      / 2)
                                                                                  then
                                                                                    (List.fold_right (fun x a -> if x < a then x else a)
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                     CW)
                                                                                  else
                                                                                    (List.fold_right (fun x a -> if x < a then x else a)
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                     CCW)).0;
                                                                                 direction =
                                                                                 Some
                                                                                 (if (foldi
                                                                                      ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                       0)
                                                                                      None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                      (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                     <
                                                                                     (List.length
                                                                                      (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                      / 2)
                                                                                  then
                                                                                    (List.fold_right (fun x a -> if x < a then x else a)
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                     CW)
                                                                                  else
                                                                                    (List.fold_right (fun x a -> if x < a then x else a)
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                     (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                     CCW)).1;
                                                                                 incoming = None; outgoing = None}
                                                                            else
                                                                            if (if (foldi
                                                                                    ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                     0)
                                                                                    None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                    (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                   <
                                                                                   (List.length
                                                                                    (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                    / 2)
                                                                                then
                                                                                  (List.fold_right (fun x a -> if x < a then x else a)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                   CW)
                                                                                else
                                                                                  (List.fold_right (fun x a -> if x < a then x else a)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                   CCW)).0
                                                                               > 25000
                                                                            then
                                                                              {mode = Driving; min_range = None; direction = None;
                                                                               incoming = None; outgoing = None}
                                                                            else
                                                                            if (if (foldi
                                                                                    ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                     0)
                                                                                    None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                    (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                   <
                                                                                   (List.length
                                                                                    (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                    / 2)
                                                                                then
                                                                                  (List.fold_right (fun x a -> if x < a then x else a)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                   CW)
                                                                                else
                                                                                  (List.fold_right (fun x a -> if x < a then x else a)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                   CCW)).0
                                                                               > Option.get state.min_range
                                                                            then
                                                                              {mode = state.mode; min_range = state.min_range;
                                                                               direction = state.direction; incoming = None;
                                                                               outgoing = None}
                                                                            else
                                                                              {mode = Turning;
                                                                               min_range =
                                                                               Some
                                                                               (if (foldi
                                                                                    ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                     0)
                                                                                    None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                    (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                   <
                                                                                   (List.length
                                                                                    (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                    / 2)
                                                                                then
                                                                                  (List.fold_right (fun x a -> if x < a then x else a)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                   CW)
                                                                                else
                                                                                  (List.fold_right (fun x a -> if x < a then x else a)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                   CCW)).0;
                                                                               direction =
                                                                               Some
                                                                               (if (foldi
                                                                                    ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                     0)
                                                                                    None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                    (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                                   <
                                                                                   (List.length
                                                                                    (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                    / 2)
                                                                                then
                                                                                  (List.fold_right (fun x a -> if x < a then x else a)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                   CW)
                                                                                else
                                                                                  (List.fold_right (fun x a -> if x < a then x else a)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                   CCW)).1;
                                                                               incoming = None; outgoing = None}
                                                                          else
                                                                          if state.mode = Driving
                                                                          then
                                                                            {mode = state.mode; min_range = state.min_range;
                                                                             direction = state.direction; incoming = None;
                                                                             outgoing =
                                                                             Some
                                                                             (Twist
                                                                              {Geometry_msgs.twist_linear =
                                                                               {Geometry_msgs.vector3_x = 10000;
                                                                                Geometry_msgs.vector3_y = 0; Geometry_msgs.vector3_z = 0};
                                                                               Geometry_msgs.twist_angular =
                                                                               {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                                Geometry_msgs.vector3_z = 0}})}
                                                                          else
                                                                          if state.direction = None
                                                                             || Is_a(Some, state.direction)
                                                                                && Option.get state.direction = CW
                                                                          then
                                                                            {mode = state.mode; min_range = state.min_range;
                                                                             direction = state.direction; incoming = None;
                                                                             outgoing =
                                                                             Some
                                                                             (Twist
                                                                              {Geometry_msgs.twist_linear =
                                                                               {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                                Geometry_msgs.vector3_z = 0};
                                                                               Geometry_msgs.twist_angular =
                                                                               {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                                Geometry_msgs.vector3_z = 10000}})}
                                                                          else
                                                                            {mode = state.mode; min_range = state.min_range;
                                                                             direction = state.direction; incoming = None;
                                                                             outgoing =
                                                                             Some
                                                                             (Twist
                                                                              {Geometry_msgs.twist_linear =
                                                                               {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                                Geometry_msgs.vector3_z = 0};
                                                                               Geometry_msgs.twist_angular =
                                                                               {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                                Geometry_msgs.vector3_z = -10000}})}).mode
                                                                         = Turning).
                                                              
                                                              1 nontautological subgoal.
                                                              
                                                              Subgoal 1:
                                                              
                                                               H0. ((state.incoming = None
                                                                     || Is_a(Some, state.incoming)
                                                                        && Is_a(Clock, Option.get state.incoming))
                                                                    || not
                                                                       (not
                                                                        ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                         = [])
                                                                        && not
                                                                           (20000 <=
                                                                            List.fold_right (fun x a -> if x < a then x else a)
                                                                            (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                            (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges)))
                                                                   || (if state.incoming = None then state
                                                                       else
                                                                       if Is_a(Sensor, Option.get state.incoming)
                                                                       then
                                                                         if state.mode = Driving
                                                                         then
                                                                           if 20000 <=
                                                                              (if (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                                  <=
                                                                                  (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)).0
                                                                           then
                                                                             {mode = Driving; min_range = None; direction = None;
                                                                              incoming = None; outgoing = None}
                                                                           else
                                                                             {mode = Turning;
                                                                              min_range =
                                                                              Some
                                                                              (if (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                                  <=
                                                                                  (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)).0;
                                                                              direction =
                                                                              Some
                                                                              (if (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                                  <=
                                                                                  (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)).1;
                                                                              incoming = None; outgoing = None}
                                                                         else
                                                                         if state.min_range = None && state.mode = Turning
                                                                         then
                                                                           if (if (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                                  <=
                                                                                  (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)).0
                                                                              <= 25000
                                                                           then
                                                                             {mode = Turning;
                                                                              min_range =
                                                                              Some
                                                                              (if (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                                  <=
                                                                                  (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)).0;
                                                                              direction =
                                                                              Some
                                                                              (if (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                                  <=
                                                                                  (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)).1;
                                                                              incoming = None; outgoing = None}
                                                                           else
                                                                             {mode = Driving; min_range = None; direction = None;
                                                                              incoming = None; outgoing = None}
                                                                         else
                                                                         if (if (List.length
                                                                                 (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                 / 2)
                                                                                <=
                                                                                (foldi
                                                                                 ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                  0)
                                                                                 None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                 (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                             then
                                                                               (List.fold_right (fun x a -> if x < a then x else a)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                CCW)
                                                                             else
                                                                               (List.fold_right (fun x a -> if x < a then x else a)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                CW)).0
                                                                            <= 25000
                                                                         then
                                                                           if (if (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                                  <=
                                                                                  (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)).0
                                                                              <= Option.get state.min_range
                                                                           then
                                                                             {mode = Turning;
                                                                              min_range =
                                                                              Some
                                                                              (if (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                                  <=
                                                                                  (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)).0;
                                                                              direction =
                                                                              Some
                                                                              (if (List.length
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   / 2)
                                                                                  <=
                                                                                  (foldi
                                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                    0)
                                                                                   None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                               then
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CCW)
                                                                               else
                                                                                 (List.fold_right (fun x a -> if x < a then x else a)
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                  (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                                  CW)).1;
                                                                              incoming = None; outgoing = None}
                                                                           else
                                                                             {mode = state.mode; min_range = state.min_range;
                                                                              direction = state.direction; incoming = None; outgoing = None}
                                                                         else
                                                                           {mode = Driving; min_range = None; direction = None;
                                                                            incoming = None; outgoing = None}
                                                                       else
                                                                       if state.mode = Driving
                                                                       then
                                                                         {mode = state.mode; min_range = state.min_range;
                                                                          direction = state.direction; incoming = None;
                                                                          outgoing =
                                                                          Some
                                                                          (Twist
                                                                           {Geometry_msgs.twist_linear =
                                                                            {Geometry_msgs.vector3_x = 10000; Geometry_msgs.vector3_y = 0;
                                                                             Geometry_msgs.vector3_z = 0};
                                                                            Geometry_msgs.twist_angular =
                                                                            {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                             Geometry_msgs.vector3_z = 0}})}
                                                                       else
                                                                       if state.direction = None
                                                                          || Is_a(Some, state.direction) && Option.get state.direction = CW
                                                                       then
                                                                         {mode = state.mode; min_range = state.min_range;
                                                                          direction = state.direction; incoming = None;
                                                                          outgoing =
                                                                          Some
                                                                          (Twist
                                                                           {Geometry_msgs.twist_linear =
                                                                            {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                             Geometry_msgs.vector3_z = 0};
                                                                            Geometry_msgs.twist_angular =
                                                                            {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                             Geometry_msgs.vector3_z = 10000}})}
                                                                       else
                                                                         {mode = state.mode; min_range = state.min_range;
                                                                          direction = state.direction; incoming = None;
                                                                          outgoing =
                                                                          Some
                                                                          (Twist
                                                                           {Geometry_msgs.twist_linear =
                                                                            {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                             Geometry_msgs.vector3_z = 0};
                                                                            Geometry_msgs.twist_angular =
                                                                            {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                             Geometry_msgs.vector3_z = -10000}})}).mode
                                                                      = Turning
                                                               H1. not
                                                                   (List.exists under_threshold
                                                                    (if Is_a(Sensor, Option.get state.incoming)
                                                                        && Is_a(Some, state.incoming)
                                                                     then
                                                                       (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                     else []))
                                                                   || not
                                                                      (20000 <=
                                                                       List.fold_right (fun x a -> if x < a then x else a)
                                                                       (if Is_a(Sensor, Option.get state.incoming)
                                                                           && Is_a(Some, state.incoming)
                                                                        then
                                                                          (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                        else 0)
                                                                       (if Is_a(Sensor, Option.get state.incoming)
                                                                           && Is_a(Some, state.incoming)
                                                                        then
                                                                          (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                        else []))
                                                               H2. not
                                                                   ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                    = [])
                                                               H3. List.exists under_threshold
                                                                   (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                              |---------------------------------------------------------------------------
                                                               C0. state.incoming = None
                                                               C1. Is_a(Some, state.incoming) && Is_a(Clock, Option.get state.incoming)
                                                               C2. (if state.incoming = None then state
                                                                    else
                                                                    if Is_a(Sensor, Option.get state.incoming)
                                                                    then
                                                                      if state.mode = Driving
                                                                      then
                                                                        if 20000 <=
                                                                           (if (List.length
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                / 2)
                                                                               <=
                                                                               (foldi
                                                                                ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                 0)
                                                                                None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                            then
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CCW)
                                                                            else
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CW)).0
                                                                        then
                                                                          {mode = Driving; min_range = None; direction = None;
                                                                           incoming = None; outgoing = None}
                                                                        else
                                                                          {mode = Turning;
                                                                           min_range =
                                                                           Some
                                                                           (if (List.length
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                / 2)
                                                                               <=
                                                                               (foldi
                                                                                ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                 0)
                                                                                None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                            then
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CCW)
                                                                            else
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CW)).0;
                                                                           direction =
                                                                           Some
                                                                           (if (List.length
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                / 2)
                                                                               <=
                                                                               (foldi
                                                                                ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                 0)
                                                                                None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                            then
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CCW)
                                                                            else
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CW)).1;
                                                                           incoming = None; outgoing = None}
                                                                      else
                                                                      if state.min_range = None && state.mode = Turning
                                                                      then
                                                                        if (if (List.length
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                / 2)
                                                                               <=
                                                                               (foldi
                                                                                ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                 0)
                                                                                None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                            then
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CCW)
                                                                            else
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CW)).0
                                                                           <= 25000
                                                                        then
                                                                          {mode = Turning;
                                                                           min_range =
                                                                           Some
                                                                           (if (List.length
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                / 2)
                                                                               <=
                                                                               (foldi
                                                                                ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                 0)
                                                                                None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                            then
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CCW)
                                                                            else
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CW)).0;
                                                                           direction =
                                                                           Some
                                                                           (if (List.length
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                / 2)
                                                                               <=
                                                                               (foldi
                                                                                ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                 0)
                                                                                None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                            then
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CCW)
                                                                            else
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CW)).1;
                                                                           incoming = None; outgoing = None}
                                                                        else
                                                                          {mode = Driving; min_range = None; direction = None;
                                                                           incoming = None; outgoing = None}
                                                                      else
                                                                      if (if (List.length
                                                                              (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                              / 2)
                                                                             <=
                                                                             (foldi
                                                                              ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                               0)
                                                                              None (fun i a b -> if a < fst b then (a, i) else b)
                                                                              (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                          then
                                                                            (List.fold_right (fun x a -> if x < a then x else a)
                                                                             (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                             (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                             CCW)
                                                                          else
                                                                            (List.fold_right (fun x a -> if x < a then x else a)
                                                                             (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                             (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                             CW)).0
                                                                         <= 25000
                                                                      then
                                                                        if (if (List.length
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                / 2)
                                                                               <=
                                                                               (foldi
                                                                                ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                 0)
                                                                                None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                            then
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CCW)
                                                                            else
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CW)).0
                                                                           <= Option.get state.min_range
                                                                        then
                                                                          {mode = Turning;
                                                                           min_range =
                                                                           Some
                                                                           (if (List.length
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                / 2)
                                                                               <=
                                                                               (foldi
                                                                                ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                 0)
                                                                                None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                            then
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CCW)
                                                                            else
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CW)).0;
                                                                           direction =
                                                                           Some
                                                                           (if (List.length
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                / 2)
                                                                               <=
                                                                               (foldi
                                                                                ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max,
                                                                                 0)
                                                                                None (fun i a b -> if a < fst b then (a, i) else b)
                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges).1
                                                                            then
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CCW)
                                                                            else
                                                                              (List.fold_right (fun x a -> if x < a then x else a)
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges,
                                                                               CW)).1;
                                                                           incoming = None; outgoing = None}
                                                                        else
                                                                          {mode = state.mode; min_range = state.min_range;
                                                                           direction = state.direction; incoming = None; outgoing = None}
                                                                      else
                                                                        {mode = Driving; min_range = None; direction = None;
                                                                         incoming = None; outgoing = None}
                                                                    else
                                                                    if state.mode = Driving
                                                                    then
                                                                      {mode = state.mode; min_range = state.min_range;
                                                                       direction = state.direction; incoming = None;
                                                                       outgoing =
                                                                       Some
                                                                       (Twist
                                                                        {Geometry_msgs.twist_linear =
                                                                         {Geometry_msgs.vector3_x = 10000; Geometry_msgs.vector3_y = 0;
                                                                          Geometry_msgs.vector3_z = 0};
                                                                         Geometry_msgs.twist_angular =
                                                                         {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                          Geometry_msgs.vector3_z = 0}})}
                                                                    else
                                                                    if state.direction = None
                                                                       || Is_a(Some, state.direction) && Option.get state.direction = CW
                                                                    then
                                                                      {mode = state.mode; min_range = state.min_range;
                                                                       direction = state.direction; incoming = None;
                                                                       outgoing =
                                                                       Some
                                                                       (Twist
                                                                        {Geometry_msgs.twist_linear =
                                                                         {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                          Geometry_msgs.vector3_z = 0};
                                                                         Geometry_msgs.twist_angular =
                                                                         {Geometry_msgs.vector3_x = 0; Geometry_msgs.vector3_y = 0;
                                                                          Geometry_msgs.vector3_z = 10000}})}
                                                                    else
                                                                      {mode = state.mode; min_range = state.min_range;
                                                                       direction = state.direction; incoming = None;
                                                                       outgoing =
                                                                       Some
                                                                       (Twist
                                                                        {Geometry_msgs.twist_linear =
                                                                         {Geometry_msgs.vector3_x = 0; Geomet
                                                              Proved
                                                              proof
                                                              ground_instances0
                                                              definitions9
                                                              inductions1
                                                              search_time
                                                              0.172s
                                                              Expand
                                                              • start[0.172s, "Goal"]
                                                                  List.exists under_threshold :var_0:
                                                                  ==> List.fold_right (fun x a -> if x < a then x else a) :var_1: :var_0: <
                                                                      20000
                                                              • subproof

                                                                not (List.exists under_threshold lst) || not (20000 <= List.fold_right (fun x a -> if x < a then x else a) max lst)
                                                                • start[0.172s, "1"]
                                                                    not (List.exists under_threshold lst)
                                                                    || not
                                                                       (20000 <= List.fold_right (fun x a -> if x < a then x else a) max lst)
                                                                • induction on (functional )
                                                                  :scheme (lst = []
                                                                           && not
                                                                              (not
                                                                               (List.hd lst <
                                                                                List.fold_right (fun x a -> if x < a then x else a) max
                                                                                (List.tl lst))
                                                                               && not (lst = []))
                                                                           ==> φ lst max)
                                                                          && (not (lst = [])
                                                                              && not
                                                                                 (List.hd lst <
                                                                                  List.fold_right (fun x a -> if x < a then x else a) max
                                                                                  (List.tl lst))
                                                                                 && φ (List.tl lst) max
                                                                              ==> φ lst max)
                                                                             && (not (lst = []) && φ (List.tl lst) max ==> φ lst max)
                                                                • Split ((((not
                                                                            (lst = []
                                                                             && not
                                                                                (List.fold_right (fun x a -> if x < a then x else a) max
                                                                                 (List.tl lst) <= List.hd lst && not (lst = [])))
                                                                            || not (List.exists under_threshold lst))
                                                                           || not
                                                                              (20000 <=
                                                                               List.fold_right (fun x a -> if x < a then x else a) max lst))
                                                                          && ((not
                                                                               ((not (lst = [])
                                                                                 && List.fold_right (fun x a -> if x < a then x else a) max
                                                                                    (List.tl lst) <= List.hd lst)
                                                                                && (not (List.exists under_threshold (List.tl lst))
                                                                                    || not
                                                                                       (20000 <=
                                                                                        List.fold_right (fun x a -> if x < a then x else a) max
                                                                                        (List.tl lst))))
                                                                               || not (List.exists under_threshold lst))
                                                                              || not
                                                                                 (20000 <=
                                                                                  List.fold_right (fun x a -> if x < a then x else a) max lst)))
                                                                         && ((not
                                                                              (not (lst = [])
                                                                               && (not (List.exists under_threshold (List.tl lst))
                                                                                   || not
                                                                                      (20000 <=
                                                                                       List.fold_right (fun x a -> if x < a then x else a) max
                                                                                       (List.tl lst))))
                                                                              || not (List.exists under_threshold lst))
                                                                             || not
                                                                                (20000 <=
                                                                                 List.fold_right (fun x a -> if x < a then x else a) max lst))
                                                                         :cases [((not (lst = [])
                                                                                   || List.fold_right (fun x a -> if x < a then x else a) max
                                                                                      (List.tl lst) <= List.hd lst && not (lst = []))
                                                                                  || not (List.exists under_threshold lst))
                                                                                 || not
                                                                                    (20000 <=
                                                                                     List.fold_right (fun x a -> if x < a then x else a) max
                                                                                     lst);
                                                                                 (((lst = []
                                                                                    || not
                                                                                       (List.fold_right (fun x a -> if x < a then x else a) max
                                                                                        (List.tl lst) <= List.hd lst))
                                                                                   || not
                                                                                      (not (List.exists under_threshold (List.tl lst))
                                                                                       || not
                                                                                          (20000 <=
                                                                                           List.fold_right (fun x a -> if x < a then x else a)
                                                                                           max (List.tl lst))))
                                                                                  || not (List.exists under_threshold lst))
                                                                                 || not
                                                                                    (20000 <=
                                                                                     List.fold_right (fun x a -> if x < a then x else a) max
                                                                                     lst);
                                                                                 ((lst = []
                                                                                   || not
                                                                                      (not (List.exists under_threshold (List.tl lst))
                                                                                       || not
                                                                                          (20000 <=
                                                                                           List.fold_right (fun x a -> if x < a then x else a)
                                                                                           max (List.tl lst))))
                                                                                  || not (List.exists under_threshold lst))
                                                                                 || not
                                                                                    (20000 <=
                                                                                     List.fold_right (fun x a -> if x < a then x else a) max
                                                                                     lst)])
                                                                  • subproof
                                                                    ((lst = [] || not (not (List.exists under_threshold (List.tl lst)) || not (20000 <= List.fold_right (fun x a -> if x < a then x else a) max (List.tl lst)))) || not (List.exists under_threshold lst)) || not (20000 <= List.fold_right (fun x a -> if x < a then x else a) max lst)
                                                                    • start[0.124s, "1.1"]
                                                                        ((lst = []
                                                                          || not
                                                                             (not (List.exists under_threshold (List.tl lst))
                                                                              || not
                                                                                 (20000 <=
                                                                                  List.fold_right (fun x a -> if x < a then x else a) max
                                                                                  (List.tl lst))))
                                                                         || not (List.exists under_threshold lst))
                                                                        || not
                                                                           (20000 <= List.fold_right (fun x a -> if x < a then x else a) max lst)
                                                                    • simplify
                                                                      into
                                                                      true
                                                                      expansions
                                                                      [List.fold_right, List.exists, List.fold_right, List.exists]
                                                                      rewrite_steps
                                                                        forward_chaining
                                                                      • subproof
                                                                        (((lst = [] || not (List.fold_right (fun x a -> if x < a then x else a) max (List.tl lst) <= List.hd lst)) || not (not (List.exists under_threshold (List.tl lst)) || not (20000 <= List.fold_right (fun x a -> if x < a then x else a) max (List.tl lst)))) || not (List.exists under_threshold lst)) || not (20000 <= List.fold_right (fun x a -> if x < a then x else a) max lst)
                                                                        • start[0.124s, "1.2"]
                                                                            (((lst = []
                                                                               || not
                                                                                  (List.fold_right (fun x a -> if x < a then x else a) max
                                                                                   (List.tl lst) <= List.hd lst))
                                                                              || not
                                                                                 (not (List.exists under_threshold (List.tl lst))
                                                                                  || not
                                                                                     (20000 <=
                                                                                      List.fold_right (fun x a -> if x < a then x else a) max
                                                                                      (List.tl lst))))
                                                                             || not (List.exists under_threshold lst))
                                                                            || not
                                                                               (20000 <= List.fold_right (fun x a -> if x < a then x else a) max lst)
                                                                        • simplify
                                                                          into
                                                                          true
                                                                          expansions
                                                                          [List.fold_right, List.exists, List.fold_right, List.exists]
                                                                          rewrite_steps
                                                                            forward_chaining
                                                                          • subproof
                                                                            ((not (lst = []) || List.fold_right (fun x a -> if x < a then x else a) max (List.tl lst) <= List.hd lst && not (lst = [])) || not (List.exists under_threshold lst)) || not (20000 <= List.fold_right (fun x a -> if x < a then x else a) max lst)
                                                                            • start[0.124s, "1.3"]
                                                                                ((not (lst = [])
                                                                                  || List.fold_right (fun x a -> if x < a then x else a) max (List.tl lst)
                                                                                     <= List.hd lst && not (lst = []))
                                                                                 || not (List.exists under_threshold lst))
                                                                                || not
                                                                                   (20000 <= List.fold_right (fun x a -> if x < a then x else a) max lst)
                                                                            • simplify
                                                                              into
                                                                              true
                                                                              expansions
                                                                              List.exists
                                                                              rewrite_steps
                                                                                forward_chaining
                                                                          Proved
                                                                          proof
                                                                          ground_instances0
                                                                          definitions1
                                                                          inductions0
                                                                          search_time
                                                                          0.078s
                                                                          Expand
                                                                          • start[0.078s, "Goal"]
                                                                              (if :var_0:.incoming = None
                                                                                  || Is_a(Some, :var_0:.incoming)
                                                                                     && Is_a(Clock, Option.get :var_0:.incoming)
                                                                               then true
                                                                               else
                                                                                 (not
                                                                                  ((Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   = [])
                                                                                  && List.fold_right (fun x a -> if x < a then x else a)
                                                                                     (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_range_max
                                                                                     (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges
                                                                                     < 20000
                                                                                  ==> (if :var_0:.incoming = None then :var_0:
                                                                                       else
                                                                                       if Is_a(Sensor, Option.get :var_0:.incoming) then … else …).mode
                                                                                      = Turning))
                                                                              && (List.exists under_threshold
                                                                                  (if Is_a(Sensor, Option.get :var_0:.incoming)
                                                                                      && Is_a(Some, :var_0:.incoming)
                                                                                   then
                                                                                     (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges
                                                                                   else [])
                                                                                  ==> List.fold_right (fun x a -> if x < a then x else a)
                                                                                      (if Is_a(Sensor, Option.get :var_0:.incoming)
                                                                                          && Is_a(Some, :var_0:.incoming)
                                                                                       then
                                                                                         (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_range_max
                                                                                       else 0)
                                                                                      (if Is_a(Sensor, Option.get :var_0:.incoming)
                                                                                          && Is_a(Some, :var_0:.incoming)
                                                                                       then
                                                                                         (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges
                                                                                       else [])
                                                                                      < 20000)
                                                                              ==> (if :var_0:.incoming = None
                                                                                      || Is_a(Some, :var_0:.incoming)
                                                                                         && Is_a(Clock, Option.get :var_0:.incoming)
                                                                                   then true
                                                                                   else
                                                                                     not
                                                                                     ((Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges
                                                                                      = [])
                                                                                     && List.exists under_threshold
                                                                                        (Destruct(Sensor, 0, Option.get :var_0:.incoming)).Sensor_msgs.laserScan_ranges
                                                                                     ==> (if :var_0:.incoming = None then :var_0:
                                                                                          else
                                                                                          if Is_a(Sensor, Option.get :var_0:.incoming) then … else …).mode
                                                                                         = Turning)
                                                                          • subproof

                                                                            (((((not (((state.incoming = None || Is_a(Some, state.incoming) && Is_a(Clock, Option.get state.incoming)) || not (not ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges = []) && not (20000 <= List.fold_right (fun x a -> if x < a then x else a) (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges))) || (if state.incoming = None then state else if Is_a(Sensor, Option.get state.incoming) then if state.mode = Driving then … else … else if state.mode = Driving then … else …).mode = Turning) || not (not (List.exists under_threshold (if Is_a(Sensor, Option.get state.incoming) && Is_a(Some, state.incoming) then (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges else [])) || not (20000 <= List.fold_right (fun x a -> if x < a then x else a) (if Is_a(Sensor, Option.get state.incoming) && Is_a(Some, state.incoming) then (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max else 0) (if Is_a(Sensor, Option.get state.incoming) && Is_a(Some, state.incoming) then (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges else [])))) || (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges = []) || not (List.exists under_threshold (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges)) || state.incoming = None) || Is_a(Some, state.incoming) && Is_a(Clock, Option.get state.incoming)) || (if state.incoming = None then state else if Is_a(Sensor, Option.get state.incoming) then if state.mode = Driving then … else … else if state.mode = Driving then … else …).mode = Turning
                                                                            • start[0.072s, "1"]
                                                                                (((((not
                                                                                     (((state.incoming = None
                                                                                        || Is_a(Some, state.incoming)
                                                                                           && Is_a(Clock, Option.get state.incoming))
                                                                                       || not
                                                                                          (not
                                                                                           ((Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                            = [])
                                                                                           && not
                                                                                              (20000 <=
                                                                                               List.fold_right (fun x a -> if x < a then x else a)
                                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                               (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges)))
                                                                                      || (if state.incoming = None then state
                                                                                          else
                                                                                          if Is_a(Sensor, Option.get state.incoming)
                                                                                          then if state.mode = Driving then … else …
                                                                                          else if state.mode = Driving then … else …).mode
                                                                                         = Turning)
                                                                                     || not
                                                                                        (not
                                                                                         (List.exists under_threshold
                                                                                          (if Is_a(Sensor, Option.get state.incoming)
                                                                                              && Is_a(Some, state.incoming)
                                                                                           then
                                                                                             (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                           else []))
                                                                                         || not
                                                                                            (20000 <=
                                                                                             List.fold_right (fun x a -> if x < a then x else a)
                                                                                             (if Is_a(Sensor, Option.get state.incoming)
                                                                                                 && Is_a(Some, state.incoming)
                                                                                              then
                                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_range_max
                                                                                              else 0)
                                                                                             (if Is_a(Sensor, Option.get state.incoming)
                                                                                                 && Is_a(Some, state.incoming)
                                                                                              then
                                                                                                (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                              else []))))
                                                                                    || (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges
                                                                                       = [])
                                                                                   || not
                                                                                      (List.exists under_threshold
                                                                                       (Destruct(Sensor, 0, Option.get state.incoming)).Sensor_msgs.laserScan_ranges))
                                                                                  || state.incoming = None)
                                                                                 || Is_a(Some, state.incoming) && Is_a(Clock, Option.get state.incoming))
                                                                                || (if state.incoming = None then state
                                                                                    else
                                                                                    if Is_a(Sensor, Option.get state.incoming)
                                                                                    then if state.mode = Driving then … else …
                                                                                    else if state.mode = Driving then … else …).mode
                                                                                   = Turning
                                                                            • simplify
                                                                              into
                                                                              true
                                                                              expansions
                                                                              List.fold_right
                                                                              rewrite_steps
                                                                                forward_chaining
                                                                                List.len_nonnegative