Note: This tutorial assumes that you have completed the previous tutorials: decision_making/Tutorials/FSM(C++), decision_making/Tutorials/HSM.
(!) 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.

Event Raise HSM Example

Description: Event Raise HSM

Tutorial Level: BEGINNER

Next Tutorial: The TAO Framework

Running the example

roslaunch decision_making_examples hsm_eventraise.launch

Overview

In this tutorial we will cover the creation of our Hierarchical state machine with one state containing another state machine, and a total of 3 tasks as depicted below. The source code described here can be found in decision_making_examples packages (src/EventRaise.cpp).

Notice the second FSM State Declaration, and usage of FSM Transitions, Event Handling and Task Calls, all complying with FSM C++ syntax explained in previous tutorials:

The FSM

   1 FSM(OffSpring)
   2 {
   3         FSM_STATES
   4         {
   5                 A,B
   6         }
   7         FSM_START(A);
   8         FSM_BGN
   9         {
  10                 FSM_STATE(A)
  11                 {
  12                         FSM_CALL_TASK(loop)
  13                         FSM_TRANSITIONS
  14                         {
  15                                 FSM_ON_EVENT("/Close", FSM_NEXT(B));
  16                                 FSM_ON_EVENT("/Loop", FSM_NEXT(A));
  17                         }
  18                 }
  19 
  20                 FSM_STATE(B)
  21                 {
  22                         FSM_CALL_TASK(close)// not just a printing task
  23                         FSM_TRANSITIONS
  24                 }
  25         }
  26         FSM_END
  27 }

This FSM actually gives us the inner (or "son") FSM' described as follows:

Wandering state machine

Now let's look at the wrapping FSM (or "father"):

   1 FSM(HeirarchyExample)
   2 {
   3         FSM_STATES
   4         {
   5                 X, Y
   6         }
   7         FSM_START(X);
   8         FSM_BGN
   9         {
  10                 FSM_STATE(Y)
  11                 {
  12                         FSM_CALL_TASK(ReachY) // just a printing task
  13                         FSM_TRANSITIONS
  14                 }
  15 
  16                 FSM_STATE(X)
  17                 {
  18                         FSM_CALL_FSM(OffSpring); //calling the Offspring FSM inside the state
  19                         FSM_TRANSITIONS
  20                         {
  21                                 FSM_ON_EVENT("/B", FSM_NEXT(Y));
  22                         }
  23                 }
  24         }
  25         FSM_END
  26 }

This is the complete machine, as described here:

Wandering state machine

Generated SCXML Files

   1 <?xml version="1.0"?>
   2 <scxml>
   3    <state name="HeirarchyExample" initialstate="X" id="/HeirarchyExample">
   4       <state name="Y" id="/HeirarchyExample/Y">
   5          <invoke name="TASK[ReachY]" id="/HeirarchyExample/Y/ReachY" />
   6       </state>
   7       <state name="X" id="/HeirarchyExample/X">
   8          <state name="OffSpring" initialstate="A" id="/HeirarchyExample/X/OffSpring">
   9             <state name="A" id="/HeirarchyExample/X/OffSpring/A">
  10                <invoke name="TASK[Loop]" id="/HeirarchyExample/X/OffSpring/A/Loop" />
  11                <transition event="Close" target="/HeirarchyExample/X/OffSpring/B"></transition>
  12                <transition event="Loop" target="/HeirarchyExample/X/OffSpring/A"></transition>
  13             </state>
  14             <state name="B" id="/HeirarchyExample/X/OffSpring/B">
  15                <invoke name="TASK[Close]" id="/HeirarchyExample/X/OffSpring/B/Close" />
  16             </state>
  17          </state>
  18          <transition event="B" target="/HeirarchyExample/Y"></transition>
  19       </state>
  20    </state>
  21 </scxml>

   1 <?xml version="1.0"?>
   2 <scxml>
   3    <state name="OffSpring" initialstate="A" id="/HeirarchyExample/X/OffSpring">
   4       <state name="A" id="/HeirarchyExample/X/OffSpring/A">
   5          <invoke name="TASK[Loop]" id="/HeirarchyExample/X/OffSpring/A/Loop" />
   6          <transition event="Close" target="/HeirarchyExample/X/OffSpring/B"></transition>
   7          <transition event="Loop" target="/HeirarchyExample/X/OffSpring/A"></transition>
   8       </state>
   9       <state name="B" id="/HeirarchyExample/X/OffSpring/B">
  10          <invoke name="TASK[Close]" id="/HeirarchyExample/X/OffSpring/B/Close" />
  11       </state>
  12    </state>
  13 </scxml>

Tasks

As shown, we use two states X and Y (Y containing a task), and X contains another FSM with two more states (with a task each). the tasks in this example shows various possibilities: one will only give us a small print-out for examples sake, another will implement usage of preemptive waiting (explained below), and one will raise an internal event to it's "father" FSM to catch. the tasks are reachTask() and closeTask() and loopTask(), implementations are as follows:

   1 decision_making::TaskResult reachTask(string name, const FSMCallContext& context, EventQueue& eventQueue){
   2                 ROS_INFO("I have reached Y state!");
   3                 boost::this_thread::sleep(boost::posix_time::milliseconds(10000));
   4         return decision_making::TaskResult::SUCCESS();
   5 }
   6 decision_making::TaskResult closeTask(string name, const FSMCallContext& context, EventQueue& eventQueue){
   7                 ROS_INFO("OffSpring State B - closing machine");
   8                 boost::this_thread::sleep(boost::posix_time::milliseconds(1000));
   9                 eventQueue.raiseEvent("/B");
  10         return decision_making::TaskResult::SUCCESS();
  11 }
  12 
  13 decision_making::TaskResult loopTask(string name, const FSMCallContext& context, EventQueue& eventQueue){
  14         ROS_INFO("OffSpring State A - Loop");
  15 
  16         //"Close" will come from an outside event!
  17         while(!preemptiveWait(1000, eventQueue)){
  18                 ROS_INFO("Looping");
  19         }
  20     return TaskResult::SUCCESS();
  21 }

Tasks registration

As you may have noticed, in the state machine we call for tasks loop, closeand ReachY but the actual names of task methods are closeTask, reachTask and loopTask, so we need to bind task names to actual methods:

   1     LocalTasks::registrate("ReachY", reachTask);
   2     LocalTasks::registrate("close", closeTask);
   3     LocalTasks::registrate("loop", loopTask);

Events

Lets look at our task methods again:

Internal (/B)

The closeTask() raises an internal Event, the logic is that the internal FSM raises an event to its "father" FSM, also pointed out below:

   1 decision_making::TaskResult closeTask(string name, const FSMCallContext& context, EventQueue& eventQueue){
   2                 ROS_INFO("OffSpring State B - closing machine");
   3                 boost::this_thread::sleep(boost::posix_time::milliseconds(1000));
   4                 eventQueue.raiseEvent("/B");
   5         return decision_making::TaskResult::SUCCESS();
   6 }

   1                 FSM_STATE(X)
   2                 {
   3                         FSM_CALL_FSM(OffSpring); //calling the Offspring FSM inside the state
   4                         FSM_TRANSITIONS
   5                         {
   6                                 FSM_ON_EVENT("/B", FSM_NEXT(Y));
   7                         }
   8                 }

External Pre-Emptive (Close/Loop)

As mentioned in the previous tutorial, we will use Preemptive Waiting - One of our tasks already raises an internal event, in this example our task will run as long as they don't receive an event from an External source, using preemptive waiting.

   1 decision_making::TaskResult loopTask(string name, const FSMCallContext& context, EventQueue& eventQueue){
   2         ROS_INFO("OffSpring State A - Loop");
   3 
   4         //"Close" will come from an outside event!
   5         while(!preemptiveWait(1000, eventQueue)){
   6                 ROS_INFO("Looping");
   7         }
   8     return TaskResult::SUCCESS();
   9 }

#!cplusplus Again a reminder from the previous tutorial, the preemption method implementation:

bool preemptiveWait(double ms, decision_making::EventQueue& queue) {
    for (int i = 0; i < 100 && !queue.isTerminated(); i++)
        boost::this_thread::sleep(boost::posix_time::milliseconds(ms / 100.0));

    return queue.isTerminated();
}

We check for an external event that will originate from src/EventRaiseTaskEvents.cpp:

   1 void publishRandomEvent(ros::Publisher& RandEventPublisher) {
   2           static random_numbers::RandomNumberGenerator randomizer;
   3           std_msgs::String event;
   4           //a condition that will come in once in a while...
   5           if((0 == randomizer.uniformInteger(1,100) % 3) && (0 == randomizer.uniformInteger(1,100) % 5)){
   6                   event.data = "Close";
   7           }
   8           else{
   9                   event.data = "Loop";
  10           }
  11           RandEventPublisher.publish(event);
  12       boost::this_thread::sleep(boost::posix_time::milliseconds(1000));
  13 }

Wiki: decision_making/Tutorials/Eventraise HSM (last edited 2014-02-05 12:21:47 by TommySM)