Wiki

Note: This tutorial assumes that you have completed the previous tutorials: decision_making/Tutorials/FSM.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Getting Started with writing FSM in C++

Description: Finite State Machine C++,SCXML and DOT representations

Keywords: decision_making

Tutorial Level: BEGINNER

Running the example

roslaunch decision_making_examples fsm_roomba.launch

Conditions and variables

Some FSM make use of internal variables. While it is possible to group those variables into events, it is often impractical since two varibles might cause multiplication of numerous event.

One example is the Roomba FSM [http://airlab.elet.polimi.it/index.php/Roomba_project]

Roomba FSM example

This FSM uses 3 variables

Coding the different values of those variables as events is possible, however it will require translation both on the FSM and the driver logic. For example:

In such a case it possible to use FSM_ON_CONDITION macro, which checks for a predicate (boolean condition). It will now be the users responsibility to update values for variables (by reading from different ros topics) and to record the external topics in case replay is needed.

First we will define the following variables

Toggle line numbers
   1 bool leftBumper, rightBumper, wallSensor;

Then it is possible to use them inside FSM_ON_CONDITION

Toggle line numbers
   1 FSM(Roomba)
   2 {
   3         FSM_STATES
   4         {
   5                 findWall,
   6                 turnSx,
   7                 correctSx,
   8                 correctDx
   9         }
  10         FSM_START(findWall);
  11         FSM_BGN
  12         {
  13                 FSM_STATE(findWall)
  14                 {
  15                         FSM_TRANSITIONS
  16                         {
  17                                 FSM_ON_CONDITION(
  18                                     leftBumper==1||rightBumper==1 ,
  19                                     FSM_NEXT(turnSx)
  20                                 );
  21                         }
  22                 }
  23                 FSM_STATE(turnSx)
  24                 {
  25 
  26                         FSM_TRANSITIONS
  27                         {
  28                                 FSM_ON_CONDITION(
  29                                     leftBumper==0&&rightBumper==0 ,
  30                                     FSM_NEXT(correctDx)
  31                                 );
  32                         }
  33                 }
  34                 FSM_STATE(correctSx)
  35                 {
  36 
  37                         FSM_TRANSITIONS
  38                         {
  39                                 FSM_ON_CONDITION(
  40                                     leftBumper==1||rightBumper==1 ,
  41                                     FSM_NEXT(turnSx)
  42                                 );
  43                                 FSM_ON_CONDITION(
  44                                     wallSensor==0 ,
  45                                     FSM_NEXT(correctDx)
  46                                 );
  47                         }
  48                 }
  49                 FSM_STATE(correctDx)
  50                 {
  51 
  52                         FSM_TRANSITIONS
  53                         {
  54                                 FSM_ON_CONDITION(
  55                                     leftBumper==1||rightBumper==1 ,
  56                                     FSM_NEXT(turnSx)
  57                                 );
  58                                 FSM_ON_CONDITION(
  59                                     wallSensor==1 ,
  60                                     FSM_NEXT(correctSx)
  61                                 );
  62                         }
  63                 }
  64         }
  65         FSM_END
  66 }

The code above generates the following scxml:

Toggle line numbers
   1 <?xml version="1.0"?>
   2 <!-- from file: src/example3.cpp -->
   3 <scxml>
   4    <state name="Roomba" initialstate="findWall" id="/Roomba">
   5       <state name="findWall" id="/Roomba/findWall">
   6          <transition event="leftBumper==1||rightBumper==1" target="/Roomba/turnSx">
   7          </transition>
   8       </state>
   9       <state name="turnSx" id="/Roomba/turnSx">
  10          <transition event="leftBumper==0&&rightBumper==0"
  11                      target="/Roomba/correctDx">
  12          </transition>
  13       </state>
  14       <state name="correctSx" id="/Roomba/correctSx">
  15          <transition event="leftBumper==1||rightBumper==1" target="/Roomba/turnSx">
  16          </transition>
  17          <transition event="wallSensor==0" target="/Roomba/correctDx"></transition>
  18       </state>
  19       <state name="correctDx" id="/Roomba/correctDx">
  20          <transition event="leftBumper==1||rightBumper==1" target="/Roomba/turnSx">
  21          </transition>
  22          <transition event="wallSensor==1" target="/Roomba/correctSx"></transition>
  23       </state>
  24    </state>
  25 </scxml>

The following dot file is generated from the xml Roomba FSM example

Create a new tutorial:

Wiki: decision_making_examples/Tutorials/Roomba (last edited 2014-01-12 14:46:23 by IgorMakhtes)