Warning: strlen() expects parameter 1 to be string, array given in /home/sharpr6/public_html/wp-content/themes/starscape/code/starscape.php on line 450
Architecture | SharpRobotica.com - Sharp ideas for the software side of robotics
Posts Tagged ‘Architecture’

InteRRaP Hybrid Architecture for Robotic & Multi-Agent Systems

datePosted on 05:32, January 22nd, 2011 by Billy McCafferty
Over the years, a number of well defined architectures have been proposed for a wide assortment of project domains; a few examples were described in Architectural Paradigms of Robotic Control.  As described, the architectural approaches can typically be categorized as follows:
  • Reactive architectures which emphasize reacting to the immediate world environment without keeping an internal world model representation,
  • Deliberative architectures which focus on maintaining a detailed internal world model, carefully planning actions to interact with the environment, and a layered system to disseminate plans to actuators,
  • Interactive architectures which focus on communication and cooperation within multi-agent systems, and
  • Hybrid architectures which provide a balance of reaction, deliberation, and/or multi-agent coordination.
As with any project, a challenge is picking the appropriate architecture for the task at hand.  Thankfully, much work has been done on analyzing agent-oriented architectures to assist development teams with making this selection.  While a little dated, Jörg Müller et al.’s Intelligent Agents V provides a solid introduction to analyzing architectural approaches and comparing them to one another for particular project needs.  For the project at hand, only those architectures which were hybrid, supporting deliberative-reaction capabilities, were considered.  Furthermore, those supporting multi-agent coordination were particularly preferred.  Specifically, the following architectures were considered in detail:  RAPs/ATLANTIS/3T, Lyons & Hendriks, TouringMachines, InteRRaP, SimAgent, and NMRA.  Without going into details as to why the choice was made, InteRRaP has been selected as the target architectural design for the project, providing a good balance of reactive and deliberative capabilities while supporting multi-agent communication and cooperation.  This post introduces the major concepts of InteRRaP and the effects of this architectural selection on the O-MaSE project methodology.

InteRRaP 4.0

InteRRaP is a hybrid, belief-desire-intention (BDI) architecture supporting the modeling of reactive, goal-directed, and interacting agents by providing 1) a set of hierarchical control layers, 2) a knowledge base that supports the representation of different abstraction levels of knowledge, and 3) a well-defined control structure that ensures coherent interaction among the control layers. [1]  For completeness, BDI should be further described.  A BDI approach is broken down, conceptually, as the following mental categories [2]:
  • Beliefs of an agent expressing its expectations about the current state of the world;
  • Desire expressing preferences over future world states or courses of action;
  • Goals describing subsets of desires that an agent might pursue (including reactivelocal, and social goals);
  • Intention expresses the specific goal (or set of goals) to commit to; and
  • Plans representing sets of intentions (each representing a partial plan) to be executed to achieve goals.

It should be noted that InteRRaP is not a traditional BDI architecture; it attempts to leverage the advantages of a BDI architecture as a component of its hybrid approach to structuring multi-agent systems, distributing the mental categories over three layers.  For example, beliefs are split into three layered models:

  • world model containing beliefs about the environment,
  • mental model holding meta-level beliefs the agent has about itself, and
  • social model describing meta-level beliefs about other agents.

For action deliberation and execution, InteRRaP incorporates three hierarchical control layers described as:

  • A behavior-based layer incorporating reactivity and procedural knowledge for routine tasks.
  • A local-planning layer that provides means-ends reasoning of local tasks and produces-goal directed behavior.
  • A cooperative-planning layer enabling agent reasoning about other agents and supporting coordinated action among agents.
The initiation of actions are triggered by specific situations, which are specific subsets of the agents beliefs.  Similar to the breakdown of belief modeling and control layering, situations are classified into three separate categories:
  • Behavioral situations which are reactive situations derived purely from the world model,
  • Local planning situations which are derived from information from both the world and mental model, and
  • Cooperative planning situations which are derived from information from the world, mental and social models.

Architectural Implementation

The implementation of the control architecture itself is based on the principles of:
  • Layered control having different level of abstraction,
  • Layered knowledge base allowing restriction of the amount of information available to lower control layers,
  • Bottom-up activation wherein the next layer up only gains control if the layer below is unable to deal with the recognized situation, and
  • Top-down execution wherein each layer uses operational primitives (or Patterns of Behavior (PoB)) defined in the next lower layer to achieve its goals.

The diagram above [3] illustrates how the underlying principles were used in implementing the control architecture of InteRRaP.  There are three primary modules:  a world interface providing the agent’s perception, communication, and action interfaces with its environment; a knowledge base partitioned into three layers, consisting of the world, mental and social models described previously; and a control unit organized into the three control layers described previously (behavior-based, local-planning, and cooperative-planning).  Furthermore, each control layer has two processes including a situation recognition and goal activation (SG) process and a planning, schedule, and execution (PS) process.  Control moves from the behavior layer up until a suitable layer competent for execution is found; action is then directed back down to the behavior layer which is the only layer with direct access to sensors and actuators.

To help limit the scope of responsibility of each layer, each is limited to a respective portion of the knowledge base.  For example, the behavior-based layer only has access to the world model and can only recognize situations warranting a purely reactive response.  Conversely, the cooperative planning layer has access to the social, mental and world models, allowing it to recognize more complex situations and to plan and pass down execution commands, accordingly.

Implications on O-MaSE

As described previously, O-MaSE is a flexible methodology for the definition and design of multi-agent systems.  While choosing InteRRaP as a preferred architecture does not preclude the use of any O-MaSE tasks, it implies the introduction of a new task:  Model Situations Task.  This task would define the situations which may be recognized for taking action upon.  Going a step further along these lines, a supporting O-MaSE task may be introduced – Refine Situations Task – to better assign which control layers should be responsible for recognizing and responding to each situation.

This introductory post to InteRRaP only touches upon the major components of this architectural approach in an effort to concisely describe its intent and organization.  The interested reader is strongly encouraged to read the references found at the bottom of this post for more detailed information.  In the next post, we’ll look at some examples of how O-MaSE was used to define requirements in alignment with the selected InteRRaP architecture.

It should be noted that it is not my intention to follow InteRRaP “to a tee”; rather, I find its overall organization to be very logical and will use as inspiration for structuring current project work; for example, I could see trex-autonomy as being a suitable approach for implementing the behavior-based and local-planning layers without negating the underlying principles of InteRRaP, nor its implied organization.  Time (and a lot of trial-and-error) will tell.

Enjoy!
Billy McCafferty


References

[1]  Müller, Jörg.  1996.  The Design of Intelligent Agents.
[2] Rao, Anand and Michael Georgeff.  1995.  BDI-Agents:  From Theory to Practice.
[3]  Fischer, Klaus, Jörg Müller, and Markus Pischel.  1995.  Unifying Control in a Layered Agent Architecture.

Part VI: Adding a UI Layer to the Package

As the last and final chapter to this series of posts (Part I, II, III, IV, V), we’ll be adding a basic UI layer to facilitate user interaction with the underlying layers of our package. Specifically, a UI will be developed to allow the user (e.g., you) to start and stop the laser reporting application service via a wxWidgets interface. If you’re new to wxWidgets, it really is a terrific open-source UI package with very helpful online tutorials, a thriving community, and a very helpful book, Cross-Platform GUI Programming with wxWidgets – certainly a good reference to add to the bookshelf. Arguably, the sample code discussed below is very simplistic and only touches upon wxWidgets; with that said, it should demonstrate how to put the basics in place and to see how the UI layer interacts with the other layers of the package.

Developing a UI layer with wxWidgets is quite straight forward; the UI itself is made up of two primary elements: a wxApp which is used to initialize the UI and a wxFrame which serves as the primary window. For the task at hand, the wxApp in the UI layer will be used to perform three primary tasks, in the order listed:

  1. Initialize ROS,
  2. Initialize application services and dependencies for those services (e.g., message endpoints), and
  3. Create the initial frame/window; application services will be passed to the frame to enable wiring up UI events to the respective application service functions.

As a rule of thumb, the UI layer should only communicate to the rest of the package elements via the application services layer. E.g., the UI layer should not be invoking functions directly on domain objects found within ladar_reporter_core; instead, it should call tasks exposed by the application services layer which then coordinates and delegates activity to lower levels.

Before we delve deeper, as a reminder of what the overall class diagram looks like, as developed over the previous posts, review the class diagram found within Part V. The current objective will be to add the UI layer, as illustrated in the package diagram found within Part I. To cut to the chase and download the end result of this post, click here.

Show me the code!

1. Setup the Package Skeleton, Domain Layer, Application Services Layer, and Message Endpoint Layer

If not done already, follow the steps in Part II, III, IV, and V to get everything in place. (Or simply download the source from Part V to skip all the action packed steps leading up to this post.)

2. Install wxWidgets

Download and install wxWidgets. Instructions for Ubuntu and Debian may be found at http://wiki.wxpython.org/InstallingOnUbuntuOrDebian.

3. Define the UI events that the user may raise

Create an enum class at src/ui/UiEvents.hpp to define UI events as follows:

// UiEvents.hpp
 
#ifndef GUARD_UiEvents
#define GUARD_UiEvents
 
namespace ladar_reporter_ui
{
  enum UiEventType
  {
    UI_EVENT_Quit = 1,
    UI_EVENT_StartReporting = 2,
    UI_EVENT_StopReporting = 3
  };
}
 
#endif /* GUARD_UiEvents */

As suggested by the enum values, the user will be able to start the reporting process, stop it, and quit the application altogether.

4. Create the wxWidgets application header class

Create src/ui/LadarReporterApp.hpp containing the following code:

// LadarReporterApp.hpp
 
#include <boost/shared_ptr.hpp>
#include <ros/ros.h>
#include "LaserScanEndpoint.hpp"
#include "LaserScanReportingService.hpp"
 
namespace ladar_reporter_ui
{
  class LadarReporterApp : public wxApp
  {
    public:
      virtual bool OnInit();
      virtual int OnExit();
 
    private:
      void InitializeRos();
      void InitializeApplicationServices();
      void CreateMainWindow();
 
      char** _argvForRos;
      ros::NodeHandlePtr _nodeHandlePtr;
 
      // Application services and dependencies.
      // Stored as pointers to postpone creation until ready to initialize.
      boost::shared_ptr<ladar_reporter_core::ILaserScanEndpoint> _laserScanEndpoint;
      boost::shared_ptr<ladar_reporter_application_services::LaserScanReportingService> _laserScanReportingService;
  };
}

A few notes:

  • LadarReporterApp inherits from wxApp to create the “main” equivalent for wxWidgets.
  • OnInit() and OnExit() are events called by wxWidgets when the UI is created and upon exiting (obviously).
  • InitializeRos(), InitializeApplicationServices(), and CreateMainWindow() lay out the three primary tasks previously described.
  • _nodeHandlePtr will hold our initialized reference to ROS during the lifetime of the UI.
  • Finally, the application services and dependencies which will be leveraged by the UI are declared. While _laserScanEndpoint won’t be used by the UI directly, it’ll need to be injected into the constructor of _laserScanReportingService and will need to be kept alive so as to continue advertising on its respective topic.

5. Create the wxWidgets application implementation class

Create src/ui/LadarReporterApp.cpp containing the following code:

// LadarReporterApp.cpp
 
#include <wx/wx.h>
#include "LadarReporterApp.hpp"
#include "LadarReporterFrame.hpp"
#include "LaserScanEndpoint.hpp"
#include "UiEvents.hpp"
 
using namespace ladar_reporter_application_services;
using namespace ladar_reporter_core;
using namespace ladar_reporter_message_endpoints;
 
// Inform wxWidgets what to use as the wxApp
IMPLEMENT_APP(ladar_reporter_ui::LadarReporterApp);
// Implements LadarReporterApp& wxGetApp() globally
DECLARE_APP(ladar_reporter_ui::LadarReporterApp);
 
namespace ladar_reporter_ui
{
  bool LadarReporterApp::OnInit() {
    // Order of initialization functions is critical:
    // 1) ROS must be initialized before message endpoint(s) can advertise
    InitializeRos();
 
    // 2) Application services must be initialized before being passed to UI
    InitializeApplicationServices();
 
    // 3) UI can be created with properly initialized ROS and application services
    CreateMainWindow();
 
    return true;
  }
 
  int LadarReporterApp::OnExit() {
    for (int i = 0; i < argc; ++i) {
      free(_argvForRos[i]);
    }
 
    delete [] _argvForRos;
 
    return 0;
  }
 
  void LadarReporterApp::InitializeRos() {
    // create our own copy of argv, with regular char*s.
    _argvForRos =  new char*[argc];
 
    for (int i = 0; i < argc; ++i) {
      _argvForRos[i] = strdup( wxString( argv[i] ).mb_str() );
    }
 
    ros::init(argc, _argvForRos, "ladar_reporter");
    _nodeHandlePtr.reset(new ros::NodeHandle);
  }
 
  void LadarReporterApp::InitializeApplicationServices() {
    _laserScanEndpoint = boost::shared_ptr<ILaserScanEndpoint>(
      new LaserScanEndpoint());
 
    _laserScanReportingService = boost::shared_ptr<LaserScanReportingService>(
      new LaserScanReportingService(_laserScanEndpoint));
  }
 
  void LadarReporterApp::CreateMainWindow() {
    LadarReporterFrame * frame = new LadarReporterFrame(
      _laserScanReportingService, _("Ladar Reporter"), wxPoint(50, 50), wxSize(450, 200));
 
    frame->Connect( ladar_reporter_ui::UI_EVENT_Quit, wxEVT_COMMAND_MENU_SELECTED,
      (wxObjectEventFunction) &LadarReporterFrame::OnQuit );
    frame->Connect( ladar_reporter_ui::UI_EVENT_StartReporting, wxEVT_COMMAND_MENU_SELECTED,
      (wxObjectEventFunction) &LadarReporterFrame::OnStartReporting );
    frame->Connect( ladar_reporter_ui::UI_EVENT_StopReporting, wxEVT_COMMAND_MENU_SELECTED,
      (wxObjectEventFunction) &LadarReporterFrame::OnStopReporting );
 
    frame->Show();
    SetTopWindow(frame);
  }
}

The direction for this class was taken from wxWidgets online tutorials along with reviewing the ROS turtlesim package, which is a real treasure trove for seeing how a much more sophisticated ROS UI is put together. (If you have not already, I strongly suggest you review the turtlesim code in detail.)

6. Create the wxWidgets frame header class

Now that the wxWidgets application is in place, the frame, representing the UI window itself, needs to be developed. Accordingly, create src/ui/LadarReporterFrame.hpp containing the following code:

// LadarReporterFrame.hpp
 
#ifndef GUARD_LadarReporterFrame
#define GUARD_LadarReporterFrame
 
#include <wx/wx.h>
#include "LaserScanReportingService.hpp"
 
namespace ladar_reporter_ui
{  
  class LadarReporterFrame : public wxFrame
  {
    public:
        LadarReporterFrame(
          boost::shared_ptr<ladar_reporter_application_services::LaserScanReportingService> laserScanReportingService, 
          const wxString& title, const wxPoint& pos, const wxSize& size);
        void OnQuit(wxCommandEvent& event);
        void OnStartReporting(wxCommandEvent& event);
        void OnStopReporting(wxCommandEvent& event);
 
    private:
        boost::shared_ptr<ladar_reporter_application_services::LaserScanReportingService> _laserScanReportingService;
  };
}
 
#endif /* GUARD_LadarReporterFrame */

There are a couple of interesting bits in the header:

  • The frame header declares the events which will be handled; e.g., OnQuit.
  • It accepts and stores an instance of the LaserScanReportingService in order to invoke the application service layer in response to user interaction.

7. Create the wxWidgets frame implementation class

Create src/ui/LadarReporterFrame.cpp containing the following code:

// LadarReporterFrame.cpp
 
#include "LadarReporterFrame.hpp"
#include "UiEvents.hpp"
 
using namespace ladar_reporter_application_services;
 
namespace ladar_reporter_ui
{
  LadarReporterFrame::LadarReporterFrame(
    boost::shared_ptr<LaserScanReportingService> laserScanReportingService, 
    const wxString& title, const wxPoint& pos, const wxSize& size)
      : wxFrame( NULL, -1, title, pos, size ), _laserScanReportingService(laserScanReportingService)
  {
    wxMenuBar *menuBar = new wxMenuBar;
    wxMenu *menuAction = new wxMenu;
 
    menuAction->Append( UI_EVENT_StartReporting, _("&Start Reporting") );
    menuAction->AppendSeparator();
    menuAction->Append( UI_EVENT_StopReporting, _("S&top Reporting") );
    menuAction->AppendSeparator();
    menuAction->Append( UI_EVENT_Quit, _("E&xit") );
 
    menuBar->Append(menuAction, _("&Action") );
 
    SetMenuBar(menuBar);
    CreateStatusBar();
    SetStatusText( _("Ready to begin reporting") );
  }
 
  void LadarReporterFrame::OnStartReporting(wxCommandEvent& WXUNUSED(event)) {
    _laserScanReportingService->beginReporting();
 
    SetStatusText( _("Laser scan reporting is running") );
  }
 
  void LadarReporterFrame::OnStopReporting(wxCommandEvent& WXUNUSED(event)) {
    _laserScanReportingService->stopReporting();
 
    SetStatusText( _("Laser scan reporting has been stopped") );
  }
 
  void LadarReporterFrame::OnQuit(wxCommandEvent& WXUNUSED(event)) {
    Close(true);
  }
}

A few implementation notes:

  • The LadarReporterFrame() constructor initializes the menubar for the window along with other rendering details.
  • Each of the respective events are defined, invoking the application services layer when applicable. As discussed previously, the UI should interact with the rest of the package layers via the application services, as demonstrated above.

There’s obviously a lot of wxWidgets related information which I am glossing over which is beyond the scope of these posts. The wxWidgets documentation referenced earlier should fill in any remaining gaps.

8. Configure CMake to Include the Header and Implementation

With the header and implementation classes completed for the both the wxWidgets application and frame, we need to make a couple of minor modifications to CMake for their inclusion in the build.

  1. Open /ladar_reporter/CMakeLists.txt. Under the commented line #rosbuild_gensrv(), add inclusions for wxWidgets as follows:
    find_package(wxWidgets REQUIRED)
    include(${wxWidgets_USE_FILE})
    include_directories( ${wxWidgets_INCLUDE_DIRS} )
  2. With /ladar_reporter/CMakeLists.txt still open, add a line to the include_directories statement for the following directory in order to include the wxWidgets application and frame headers:
    "src/ui"
  3. Open /ladar_reporter/src/CMakeLists.txt. Add an inclusion for the ui directory at the end of the file:
    add_subdirectory(ui)
  4. Now, in order to create the UI executable itself, a new CMake file is needed under /ladar_reporter/src/ui. Accordingly, create a new CMakeLists.txt under /ladar_reporter/src/ui, containing the following:
    rosbuild_add_executable(
      ladar_reporter_node
      LadarReporterApp.cpp
      LadarReporterFrame.cpp
    )
    
    target_link_libraries(
      ladar_reporter_node
      ladar_reporter_application_services
      ladar_reporter_message_endpoints
      # Important that core comes after application_services due to direction of dependencies
      ladar_reporter_core
      ${wxWidgets_LIBRARIES}
    )

9. Add a ROS wxWidgets Dependency to manifest.xml

Since the package will be leveraging wxWidgets, a dependency needs to be added for the package to find and use this, accordingly:

  • Under /ladar_reporter, open manifest.xml and add the following line just before the closing </package> tag:
    <rosdep name="wxwidgets"/>

10. Build and try out the UI Functionality

We are now ready to try everything out. While it is generally possible to write unit tests for the UI layer, personal experience has shown that the UI changes too frequently to make such unit tests worth while. UI unit tests quickly become a maintenance headache and do not provide much more value than what the existing unit tests have already proven; i.e., we’ve already verified through unit tests that the heart of our package – the domain objects, the message endpoints, and the application services – are all working as expected…the UI is now “simply” the final touch. Enough babble, let’s see this baby in action:

  1. Build the application by running make within a terminal at the root of the package (at /ladar_reporter).
  2. Open a new terminal and run roscore to begin ROS
  3. Open a third terminal window and run rostopic echo /laser_report to observe any laser reports published to ROS
  4. In the terminal that you’ve been building in…
    make
    cd bin
    ./ladar_reporter_tests

    Wait a second, that’s not showing anything new…that’s right! Always run your unit tests after making changes, even if you haven’t added any new tests, to make sure that you haven’t broken any existing code.

  5. Still within the bin folder – in the terminal – run ./ladar_reporter_node. A window should pop-up allowing you to select an “Action” menu to start and stop the reporting service along with quitting the application altogether. You can see the laser reports going out to ROS via the third terminal window that was opened.
  6. Click the “Quit” menu item when you just can’t handle any more excitement.

Well, that about wraps it up, we started by laying out our architecture and systematically tackling each layer of the package with proper separation of concerns and unit testing to make sure we were doing what we said we were doing. As demonstrated with the layering approach that we developed, higher layers (e.g., application services and core) didn’t depend on lower layers (e.g., message endpoints and the ROS API). In fact, when possible, the lower layers actually depended on interfaces defined in the higher layers; e.g., the message endpoint implemented an interface defined in the higher core layer. (Although the class diagrams show core on the bottom, it’s actually reflecting the dependency inversion that was introduced.) This dependency inversion enabled a clean separation of concerns while allowing us to unit test the various layers in isolation of each other.

I sincerely hope that this series has shed some light on how to properly architect a ROS package. While this series did not go into a granular level of detail with respect to using ROS and wxWidgets, it should have provided a good starting point for developing a solid package. The techniques described in this series have been honed over many years by demi-gods of development (e.g., Martin Fowler, Robert Martin, Kent Beck, Ward Cunningham, and many others) and continue to prove their value in enabling the development of maintainable, extensible applications which are enjoyable to work on. While ROS may be relatively new, the tried and trued lessons of professional development are quite timeless indeed.

As always, your feedback, questions, comments, suggestions, and even rebuttals are most welcome. To delve a bit further into many of the patterns oriented topics discussed, I recommend reading Gregor Hohpe’s Enterprise Integration Patterns and Robert Martin’s Agile Software Development, Principles, Patterns, and Practices. And obviously, for anything ROS related, you’ll want to keep reading everything you can at http://www.ros.org/wiki/ (and here at sharprobotica.com, of course)!

Enjoy!
Billy McCafferty

Download the source for this article.

Part V: Developing and Testing the ROS Message Endpoint

[Author's note, July 28, 2010: Introduced Boost::shared_ptr to manage reference to message endpoint so as to enable postponed construction, as will be required in Part VI.]

While this series (Part I, II, III, IV) has been specifically written to address writing well-designed packages for ROS, we’ve actually seen very little of ROS itself thus far. In fact, outside of the use of roscreate to generate the package basics and sensor_msgs::LaserScan for communicating laser scan data from the reader up to the application services layer, there’s been no indication that this application was actually intended to work with ROS now or ever. Ironically, this is exactly what we’d expect to see in a well designed ROS package.

Each layer that we’ve developed – as initially outlined in Part I – is logically separated from each other’s context of responsibility. To illustrate, the upper layers do not directly depend on “service” layers, such as message endpoints. Instead, the lower layers depend on abstract service interfaces declared in the upper layers. This dependency inversion was enabled in Part IV with the creation of ILaserScanEndpoint, a separated interface. If all of this dependency inversion and separated interface mumbo-jumbo has your head spinning at all, take some time to delve deeper into this subject in Dependency Injection 101.

While the actual message endpoint interface was created, only a test double was developed for testing the application service layer’s functionality. Accordingly, in this post, the concrete message endpoint “service,” which implements its separated interface, will be developed and tested. That’s right…we’ll finally actually talk to ROS! You can skip to the chase and download the source for this post.

Before digging into the code, it’s important to take a moment to better understand the purpose and usefulness of the message endpoint. The message endpoint encapsulates communications to the messaging middleware similarly to how a data repository encapsulates communications to a database. By encapsulating such communications, the rest of the application (ROS package, in our case) may remain blissfully oblivious to details such as how to publish messages to a topic or translate between messages and domain layer objects.

This separation of concerns helps to keep the application cleanly decoupled from the messaging middleware. Another benefit of this approach is enabling the development and testing of nearly the entirety of the application/package before “wiring” it up to the messaging middleware itself. This typically results in more reusable and readable code. If you haven’t already, I would encourage you to read the article Message-Based Systems for Maintainable, Asynchronous Development for a more complete discussion on message endpoints.

Onward!

Target Class Diagram

The following diagram shows what the package will look like after completing the steps in this post…it’s beginning to look oddly familiar to the package diagram discussed in Part I of this series, isn’t it? If you’ve been following along, most of the elements have already been completed; only the concrete LaserScanEndpoint and LaserScanEndpointTests will need to be introduced along with a slight modification to the TestRunner.

1. Setup the Package Skeleton, Domain Layer and Application Services Layer

If not done already, follow the steps in Part II, Part III, and Part IV to create the package and develop/test the domain and application service layers. (Or just download the code from Part IV as a starting point to save some time.)

2. Create the message endpoint header class.

Create src/message_endpoints/LaserScanEndpoint.hpp containing the following code:

// LaserScanEndpoint.hpp
 
#ifndef GUARD_LaserScanEndpoint
#define GUARD_LaserScanEndpoint
 
#include <ros/ros.h>
#include "sensor_msgs/LaserScan.h"
#include "ILaserScanEndpoint.hpp"
 
namespace ladar_reporter_message_endpoints
{
  class LaserScanEndpoint : public ladar_reporter_core::ILaserScanEndpoint
  { 
    public:
      LaserScanEndpoint();
 
      void publish(const sensor_msgs::LaserScan& laserScan) const;
 
    private:
      // Create handle to node
      ros::NodeHandle _ladarReporterNode;
 
      ros::Publisher _laserReportPublisher;
  };
}
 
#endif /* GUARD_LaserScanEndpoint */

The message endpoint header simply implements ILaserScanEndpoint and sets up handlers for holding the ROS NodeHandle and Publisher. The more interesting bits are found in the implementation details…

3. Create the message endpoint implementation class.

Create src/message_endpoints/LaserScanEndpoint.cpp containing the following code:

// LaserScanEndpoint.cpp
 
#include <ros/ros.h>
#include "sensor_msgs/LaserScan.h"
#include "LaserScanEndpoint.hpp"
 
namespace ladar_reporter_message_endpoints
{
  LaserScanEndpoint::LaserScanEndpoint() 
    // Setup topic for publishing laser scans to
    : _laserReportPublisher(
      _ladarReporterNode.advertise<sensor_msgs::LaserScan>("laser_report", 100)) { }
 
  void LaserScanEndpoint::publish(const sensor_msgs::LaserScan& laserScan) const {
    _laserReportPublisher.publish(laserScan);
    ros::spinOnce();
    ROS_INFO("Published laser scan to laser_report topic with angle_min of: %f", laserScan.angle_min);
  };
}

As you can see, there’s really not much to the actual publication process…which is what we were hoping for. The message endpoint should simply be a light way means to send and receive messages to/from the messaging middleware. This message endpoint does so as follows:

  • The constructor initializes the publisher by advertising on a topic with the name of “laser_report.”
  • The publish() function simply takes the received laserSan and moves it along to be published via ROS. Although not necessary for this specific package code, the call to spinOnce() will be important when the package has callbacks based on messages received. (See http://www.ros.org/wiki/ROS/Tutorials/WritingPublisherSubscriber(c%2B%2B) for more details.)

4. Configure CMake to Include the Header and Implementation

With the header and implementation classes completed, we need to make a couple of minor modifications to CMake for their inclusion in the build.

  1. Open /ladar_reporter/CMakeLists.txt. Within the include_directories statement, add an include for the following directory to include the concrete message endpoint header:
    "src/message_endpoints"
  2. Open /ladar_reporter/src/CMakeLists.txt. Add an inclusion for the message_endpoints directory at the end of the file:
    add_subdirectory(message_endpoints)
  3. Now, in order to create the message endpoints class library itself, a new CMake file is needed under /ladar_reporter/src/message_endpoints. Accordingly, create a new CMakeLists.txt under /ladar_reporter/src/message_endpoints, containing the following:
    # Create the library
    add_library(
      ladar_reporter_message_endpoints
      LaserScanEndpoint.cpp
    )

5. Build the message endpoints Class Library

In a terminal window, cd to /ladar_reporter and run make. The class library should build and link successfully.

Like with everything else thus far…it’s now time to test our new functionality.

6. Unit Test the LaserScanEndpoint Functionality

While testing up to this point has been pretty straight-forward, we now need to incorporate ROS package initialization within the test itself.

  1. Our package is going to act as a single ROS node; accordingly, we need to modify /ladar_reporter/test/TestRunner.cpp to initialize ROS within the package and to register itself as a node which we’ll call “ladar_reporter.” While I’m hard-coding the node name within the test itself, you may want to consider putting the name into a config file as it’ll likely be referenced in multiple places; having it centralized within a config file gets rid of the magic string, making it easier to change while reducing the likelihood of typing it wrong in some hard-to-track-down spot.

    Open /ladar_reporter/test/TestRunner.cpp and modify the code to reflect the following:

    #include <gtest/gtest.h>
    #include <ros/ros.h>
     
    // Run all the tests that were declared with TEST()
    int main(int argc, char **argv){
      testing::InitGoogleTest(&argc, argv);
     
      // Initialize ROS and set node name
      ros::init(argc, argv, "ladar_reporter");
     
      return RUN_ALL_TESTS();
    }
  2. Create a new testing class, /ladar_reporter/test/message_endpoints/LaserScanEndpointTests.cpp:
    // LaserScanEndpointTests.cpp
     
    #include <gtest/gtest.h>
    #include "sensor_msgs/LaserScan.h"
    #include "LaserScanEndpoint.hpp"
    #include "LaserScanReportingService.hpp"
     
    using namespace ladar_reporter_application_services;
    using namespace ladar_reporter_message_endpoints;
     
    namespace ladar_reporter_test_message_endpoints
    {
      // Define unit test to verify ability to publish laser scans 
      // to ROS using the concrete message endpoint.
      TEST(LaserScanEndpointTests, canPublishLaserScanWithEndpoint) {
        // Establish Context
        LaserScanEndpoint laserScanEndpoint;
        sensor_msgs::LaserScan laserScan;
     
        // Give ROS time to fully initialize and for the laserScanEndpoint to advertise
        sleep(1);
     
        // Act
        laserScan.angle_min = 1;
        laserScanEndpoint.publish(laserScan);
     
        laserScan.angle_min = 2;
        laserScanEndpoint.publish(laserScan);
     
        // Assert
        // Nothing to assert other than using terminal windows to 
        // watch publication activity. Alternatively, for better testing, 
        // you could create a subscriber and subscribe to the reports 
        // You could then track how many reports were received and 
        // assert checks, accordingly.
      }
     
      // Define unit test to verify ability to leverage the reporting 
      // service using the concrete message endpoint. This is more of a 
      // package integration test than a unit test, making sure that all 
      // of the pieces are playing together nicely within the package.
      TEST(LaserScanEndpointTests, canStartAndStopLaserScanReportingServiceWithEndpoint) {
        // Establish Context
        boost::shared_ptr<LaserScanEndpoint> laserScanEndpoint =
          boost::shared_ptr<LaserScanEndpoint>(new LaserScanEndpoint());
        LaserScanReportingService laserScanReportingService(laserScanEndpoint);
     
        // Give ROS time to fully initialize and for the laserScanEndpoint to advertise
        sleep(1);
     
        // Act
        laserScanReportingService.beginReporting();
        sleep(4);
        laserScanReportingService.stopReporting();
     
        // Assert
        // See assertion note above from 
        // LaserScanEndpointTests.canPublishLaserScanWithEndpoint
      }
    }

    The comments within the test class above should clarify what is occurring. But in summary, the canPublishLaserScanWithEndpoint test bypasses all of the layers and tests the publishing of messages directly via the message endpoint. The canStartAndStopLaserScanReportingServiceWithEndpoint test takes this much further and injects the LaserScanEndpoint message endpoint into the LaserScanReportingService application service and starts/stops the laser scan reprorting, accordingly. This latter test should be seen more as an integration test rather than a unit test as it tests the results of all of the layers working together.

  3. Open /ladar_reporter/test/CMakeLists.txt. Within the rosbuild_add_executable statement, add the following to include the message endpoint tests in the build:
    ./message_endpoints/LaserScanEndpointTests.cpp
  4. While we’re at it, we’ll also need to link the new message_endpoints class library to the unit testing executable; accordingly, also within /ladar_reporter/test/CMakeLists.txt, modify target_link_libraries to reflect the following:
    # Link the libraries
    target_link_libraries(
      ladar_reporter_tests
      ladar_reporter_application_services
      ladar_reporter_message_endpoints
      # Important that core comes after application_services due to direction of dependencies
      ladar_reporter_core
    )
  5. Verify that everything builds OK by running make within a terminal from the root folder, /ladar_reporter.
  6. Now for the fun part…time to run our tests with ROS running. The steps will follow closely to those described in the ROS tutorial, Examining Pulisher/Subscriber:
    1. Open a new terminal and run roscore to begin ROS
    2. In the terminal that you’ve been building in…
      make
      cd bin
      ./ladar_reporter_tests

    With a little luck, you should see a few messaging being published to ROS while running the unit tests. And just to prove it…

    1. With roscore still running, open a third terminal window and run rostopic echo /laser_report. You’ll likely be warned that the topic is not publishing yet…let’s change that.
    2. Back in your original terminal, the one you ran the unit tests in, rerun ./ladar_reporter_tests. You should now being seeing laser scans being echoed to the third terminal window for the LaserScanEndpointTests canPublishLaserScanWithEndpoint and canStartAndStopLaserScanReportingServiceWithEndpoint. Seriously now, how cool is that?

The first five parts of this series conclude the primary elements of developing well-designed packages for Robot Operating System (ROS) using proven design patterns and proper separation of concerns. Obviously, this is not a trivially simple approach to developing ROS packages; indeed, it would be overkill for very simple packages. But as packages grow in size, scope, and complexity, techniques described in this series should help to establish a maintainable, extensible package which doesn’t get too unruly as it evolves. In Part VI, the final part in this series, we’ll look at adding a simple UI layer, using wxWidgets, to interact with the package functionality.

Enjoy!
Billy McCafferty

Download the source for this post.

Sequencing Layer with ESL (Execution Support Language)

datePosted on 00:06, July 13th, 2010 by Billy McCafferty

In Architectural Paradigms of Robotic Control, I discussed a number of control architectures with a bias towards a hybrid approach, for facilitating reactive behaviors without precluding proper planning. With 3T, a common hybrid approach, the three layers include a skill layer for reactive behavior and actuator control, a sequencing (or execution) layer for sequencing behaviors based on relevant conditions, and a planning (or deliberative) layer for making plans for future actions.

While the skill layer is typically developed in a low level language such as C++, the sequencing and planning layers frequently require a “higher” language to manage complexity and required flexibility. (E.g., a language using XML to express and execute first-order predicate logic without worrying about the low level implementation details of C++ control structure could be considered a “higher” language.) Indeed, Douglas Hofstadter, in his classic work Gödel, Escher, Bach, suggests that such higher level languages will most certainly be a prerequisite for developing more intelligent machines.

ESL (Execution Support Language), developed by Ron Garret (the artist formerly known as Erann Gat), is one such higher language, built on Lisp, for the implementation of the sequencing layer of a hybrid control architecture. ESL is discussed in both Artificial Intelligence and Mobile Robotics and Springer Handbook of Robotics as being a language which:

  • Supports hierarchical decomposition of tasks into subtasks
  • Supports design by contract (pre/post conditions)
  • Supports signaling of state changes
  • Supports clean-up procedures
  • Exhibits robust execution monitoring and exception handling
  • Includes symbolic database (world model) for linking environment to behavior layer

After looking around for an implementation of ESL, I contacted Dr. Garret to find out where I might be able to find it. Amiably, Ron has made ESL available for download from his site. While I admit that I have not yet used ESL, I look forward to digging into Ron’s code to learn more about this seemingly solid approach to developing and managing a proper sequencing layer.

While I am also familiar with Task Description Language (TDL) as an alternative to ESL, I am quite interested in hearing about any other approaches actively being taken to managing the sequencing/execution layer. I’ll certainly post more about ESL or other options as I research more on this topic. Incidentally, I’m also looking forward to digging into Herbal for the planning layer…but that’s for another post altogether!

Enjoy!
Billy McCafferty

Part IV: Developing and Testing the Application Services

[Author's note, July 28, 2010: Introduced Boost::shared_ptr to manage reference to message endpoint so as to enable postponed construction, as will be required in Part VI.]

Ah, we’ve made it to the application services layer.  After defining the architecture, setting up the package, and implementing the core layer which contains the domain logic of the application, we’re ready to take on developing the application services layer.  In short, the service layer provides the external API to the underlying domain layer.  Ideally, one should be able to develop the entirety of the “non-UI” portions of an application and have it exposed via the application services layer.  In other words, one should be able to swap out the front end – say from a web front end to a Flash front end – without having the application services layer effected. If you’d like to go ahead and download the source for this article, click here.

The application services layer is analogous to a task or coordination manager; i.e., it doesn’t know how to carry out the low level details of a particular action but it does know who is responsible for carrying out particular tasks.  Accordingly, the application services layer of the package (or any application for that matter) is mostly made up of a number of publicly accessible methods which, in turn, pass responsibilities on to external service dependencies (e.g., a message endpoint) and the domain layer for execution.

With that said, the services layer should still eschew direct dependencies on external services, such as communications with a messaging framework (e.g., ROS).  Accordingly, in this post, we’ll materialize the application services layer of our package and give it two responsibilities:

  • Coordinate with the domain layer to begin laser report reading and handle the raised reports, accordingly;
  • Forward laser reports on to the appropriate message endpoint(s) to have the information disseminated over the message based system.

But (there’s always a “but” isn’t there), while the application services layer should be responsible for passing messages received from the domain layer on to the messaging middleware, it should not have a direct dependency on that messaging middleware itself.  This decoupling facilitates testing of the application services layer with test doubles, keeps a clean separation of concerns between task coordination and messaging, and provides greater flexibility with being able to modify/upgrade the messaging layer without affecting the application services layer.

A moment needs to be taken to clarify the differences among application services, domain services, and “external resource” services.

  • Application services are our current concern.  The word “services” in their convoluted title is misleading and should not be inferred as being web services, RESTful services, or the like.  A better name for describing the application services responsibilities is “task coordination layer,” “workflow management layer,” or “not-real-services application services layer.”  We’ll examine a bit in this post exactly how the application services layer can be properly leveraged.
  • Domain services are really utility classes used by the core layer (the concern of our previous post) for processing data or encapsulating a specific, reusable task or behavior.  Domain services almost never have state (i.e., properties) and sometimes expose behavior as static methods.  A good example of a domain service would be a calculator class (e.g., Kalman filter calculator) or a string utility class.
  • External resource services are what we typically think of when we hear the word “service.”  An external resource service is any class which depends upon…well…an external resource.  Examples of an external resource include databases, resource files (e.g., maps), messaging middleware, third party web services, and even the laser reading class that we simulated in Part II of this series.  Ideally, external resource services should be abstracted, allowing consumers of the services to interact with them via interfaces or abstract classes.  In this way, layers remain decoupled from the implementation details of the services, reflecting the benefits of proper OOP design.  Proper abstraction of service layers usually involves separated interface and dependency injection.  We’ll see in this post how these techniques are leveraged to decouple the application services layer from the message endpoints (which are indeed external resource services).

Before we delve in, let’s briefly review what we plan to accomplish:

  • An application service class – LaserScanReportingService – will be developed to provide a public API for starting and stopping the laser reader.  In addition to exposing this behavior, the class will also listen for laser scan reads and pass the laser scans onto a message endpoint for publication to ROS.
  • A message endpoint interface will be introduced to provide an abstraction to the implementation details of the concrete message endpoint itself.  The application service class will communicate with the message endpoint via this abstraction to allow for unit testing the application services layer in isolation of the messaging middleware.
  • Unit tests will be written to verify the functionality of the application service class.  Furthermore, a message endpoint test double, a stub in this case, will be added to simulate communications with the messaging middleware.  Again, this will allow us to verify the task coordination behavior of the application services layer without concerning ourselves with messaging middleware integration details.

Enough with the chatter, let’s see some code!

Target Class Diagram

The following diagram shows what the package will look like after completing the steps in this post. While the individual elements will be discussed in more detail; the class diagram should serve as a good bird’s eye view of the current objectives. The elements with green check marks were completed in previous posts.

1. Setup the Package Skeleton and Domain Layer

If not done already, follow the steps in Part II and Part III to create the package and develop/test the domain layer.

2. Create an interface for the message endpoint service which the application service layer will leverage to communicate with ROS.

Create src/core/message_endpoint_interfaces/ILaserScanEndpoint.hpp containing the following code:

// ILaserScanEndpoint.hpp
 
#ifndef GUARD_ILaserScanEndpoint
#define GUARD_ILaserScanEndpoint
 
#include "sensor_msgs/LaserScan.h"
 
namespace ladar_reporter_core
{
  class ILaserScanEndpoint
  {
    public:
      // Virtual destructor to pass pointer ownership without exposing base class [Meyers, 2005, Item 7]
      virtual ~ILaserScanEndpoint() {}
      virtual void publish(const sensor_msgs::LaserScan& laserScan) const = 0;
  };
}
 
#endif /* GUARD_ILaserScanEndpoint */

There shouldn’t be anything too surprising in this interface.  It simply exposes a method to publish a laser scan to the underlying messaging middleware.  Why not put the interface in the application services layer, which intends to use it?  A couple of good reasons come to mind: 1) since it’s a pure interface, having elements within core aware of it (or even directly dependent upon it) does not introduce any further coupling to the underlying external resource, the messaging middleware, and 2) in very simply packages, an application services layer might be overkill, so keeping the “external resource service interface” (there’s a mouthful) in the core layer facilitates either approach without having to move anything around if the selected approach changes during development.

3. Create the application service header class.

Create src/application_services/LaserScanReportingService.hpp containing the following code:

// LaserScanReportingService.hpp
 
#ifndef GUARD_LaserScanReportingService
#define GUARD_LaserScanReportingService
 
#include <boost/shared_ptr.hpp>
#include "ILaserScanEndpoint.hpp"
 
namespace ladar_reporter_application_services
{
  class LaserScanReportingService
  {
    public:
      explicit LaserScanReportingService(boost::shared_ptr<ladar_reporter_core::ILaserScanEndpoint> laserScanEndpoint);
 
      void beginReporting() const;
      void stopReporting() const;
 
    private:
      // Forward declare the implementation class
      class LaserScanReportingServiceImpl;
      boost::shared_ptr<LaserScanReportingServiceImpl> _pImpl;
  };
}
 
#endif /* GUARD_LaserScanReportingService */

A few notes:

  • Line 7:  Includes the previously defined message endpoint interface.
  • Line 14:  Provides a constructor for the application service class, accepting an implementation of ILaserScanEndpoint, accordingly.
  • Lines 16-17:  Exposes methods for exposing behavior found within the core layer.
  • Lines 21-22:  Declaration for a pImpl (private implementation) that will allow the application service class to be updated frequently while minimizing the rebuilding of other class libraries which depend upon it.  Using the pImpl pattern will likely be overkill in smaller packages, but can be an appreciable timesaver as packages grow in size. It has been included in the sample code here as a example reference for when it might be more appropriately required.

4.  Create the application service implementation class.

Create src/application_services/LaserScanReportingService.cpp containing the following code:

// LaserScanReportingService.cpp
 
#include "sensor_msgs/LaserScan.h"
#include "ILaserScanListener.hpp"
#include "LaserScanReader.hpp"
#include "LaserScanReportingService.hpp"
 
using namespace ladar_reporter_core;
 
namespace ladar_reporter_application_services
{
  // Private implementation of LaserScanReportingService
  class LaserScanReportingService::LaserScanReportingServiceImpl : public ladar_reporter_core::ILaserScanListener
  {
    public:
      explicit LaserScanReportingServiceImpl(boost::shared_ptr<ILaserScanEndpoint> laserScanEndpoint);
 
      void onLaserScanAvailableEvent(const sensor_msgs::LaserScan& laserScan) const;
      LaserScanReader laserScanReader;
 
    private:
      boost::shared_ptr<ILaserScanEndpoint> _laserScanEndpoint;
  };
 
  LaserScanReportingService::LaserScanReportingService(boost::shared_ptr<ILaserScanEndpoint> laserScanEndpoint)
    : _pImpl(new LaserScanReportingServiceImpl(laserScanEndpoint)) {
 
    // Wire up the reader to the handler of laser scan reports
    _pImpl->laserScanReader.attach(*_pImpl);
 }
 
  LaserScanReportingService::LaserScanReportingServiceImpl::LaserScanReportingServiceImpl(boost::shared_ptr<ILaserScanEndpoint> laserScanEndpoint)
    : _laserScanEndpoint(laserScanEndpoint) { }
 
  void LaserScanReportingService::beginReporting() const {
    _pImpl->laserScanReader.beginReading();
  }
 
  void LaserScanReportingService::stopReporting() const {
    _pImpl->laserScanReader.stopReading();
  }
 
  void LaserScanReportingService::LaserScanReportingServiceImpl::onLaserScanAvailableEvent(const sensor_msgs::LaserScan& laserScan) const {
    // Send laserScan to the message end point
    _laserScanEndpoint->publish(laserScan);
  };
}

A few notes:

  • LaserScanReportingService::LaserScanReportingServiceImpl defines the pImpl implementation.  As shown, this pImpl implementation accepts a ILaserScanEndpoint via its constructor and also adds members for communicating with LaserScanReader and with the provided message end point.  As discussed earlier in this post, it’s preferable to abstract dependencies on external resource services using interfaces or abstract classes, as was done with ILaserScanEndpoint.  Quite arguably, LaserScanReader is also an external resource service.  But since the core of our package is in providing a means to read laser scans from a particular laser range finder, I made a purity concession, if you will, allowing the application services layer to have a direct dependency on the reader itself.  Alternatively, an interface could be introduced for the LaserScanReader; but since the very heart of this package is in reading and reporting laser scans, I felt this concession to be warranted…or at least justifiably defendable.  With that said, concessions such as this should be carefully thought out and discussed with the project team to determine the pros and cons of either approach and to ensure that everyone has a clear understanding of the motivations of the decision.  (If the team – or yourself – does not understand or can explain why an architectural decision was made, it’s a good chance that the architectural decision will not be adhered to or may become a source of code rot.)

    The other item to note is that the pImpl class implements ILaserScanListener; accordingly, this class will act as the observer for receiving and handling laser scan reports raised from LaserScanReader.

  • The constructor of LaserScanReportingService accepts a reference to ILaserScanEndpoint, passes that reference on to the constructor of LaserScanReportingServiceImpl and attaches the observer to LaserScanReader to listen for raised laser scans.
  • The constructor of LaserScanReportingServiceImpl accepts a reference to ILaserScanEndpoint and initializes the laserScanEndpoint member to that reference, accordingly.
  • beginReporting and stopReporting provide pass through methods to the underlying behavior exposed by laserScanReader.
  • Finally, onLaserScanAvailableEvent provides an event handler to accept a laser scan from LaserScanReader and pass it on to laserScanEndpoint’s publish function.

As mentioned previously, the above implementation could be done without a private implementation design pattern, but this serves to illustrate how such a pattern may be leveraged when warranted.

5. Configure CMake to Include the Header and Implementation

With the header and implementation classes completed, we need to make a couple of minor modifications to CMake for their inclusion in the build.

  1. Open /ladar_reporter/CMakeLists.txt. Within the include_directories statement, add an include for the following directory to include the message endpoint and application service headers:
    "src/core/message_endpoint_interfaces"
    "src/application_services"
  2. Open /ladar_reporter/src/CMakeLists.txt. Add an inclusion for the application_services directory at the end of the file:
    add_subdirectory(application_services)
  3. Now, in order to create the application services class library itself, a new CMake file is needed under /ladar_reporter/src/application_services. Accordingly, create a new CMakeLists.txt under /ladar_reporter/src/application_services, containing the following:
    # Create the library
    add_library(
      ladar_reporter_application_services
      LaserScanReportingService.cpp
    )

6. Build the application services Class Library

In a terminal window, cd to /ladar_reporter and run make. The class library should build and link successfully.

Like before, we’re not done yet…it’s now time to test our new functionality.

7. Unit Test the LaserScanReportingService Functionality

When we go to test the functionality of the laser scan reporting application service, it will likely be quickly noticed that there’s a missing dependency which will be needed to test the functionality of this class: a concrete implementation of ILaserScanEndpoint.hpp. The job of the message endpoint class will be to take laser scans and publish them to the appropriate topic on ROS. But we’re just not there yet…what we’d really like to do is to be able to test the functionality of the application service layer – LaserScanReportingService.cpp to be specific – without necessitating the presence of the message endpoint and ROS itself. While we’ll have to cross that bridge eventually (in Part V to be exact), we’re not currently interested in doing integration tests. Instead, we’re only interested in testing the behavior of the application service regardless of its integration with ROS.

Accordingly, a “stub” object will be employed to stand in for an actual message endpoint. In this case, the stub object is nothing more than a concrete implementation of ILaserScanEndpoint.hpp; but instead of publishing the laser scan to ROS, it’ll do something testable, such as keep a tally, or possibly a temporary queue, of laser scans “published” which can then be verified with testing asserts. If you’re new to unit testing, you’ll want to read about test doubles, Martin Fowler’s Mocks Aren’t Stubs, and XUnit Test Patterns for a more comprehensive treatment of the subject.

Onward with testing…

  1. Create /ladar_reporter/test/message_endpoints/test_doubles/LaserScanEndpointStub.hpp containing the following code to declare and define the message endpoint stub:
    // LaserScanEndpointStub.hpp
     
    #ifndef GUARD_LaserScanEndpointStub
    #define GUARD_LaserScanEndpointStub
     
    #include "sensor_msgs/LaserScan.h"
    #include "ILaserScanEndpoint.hpp"
     
    namespace ladar_reporter_test_message_endpoints_test_doubles
    {
      class LaserScanEndpointStub : public ladar_reporter_core::ILaserScanEndpoint
      { 
        public:
          LaserScanEndpointStub()
            : countOfLaserScansPublished(0) { }
     
          void publish(const sensor_msgs::LaserScan& laserScan) const {
            countOfLaserScansPublished++;
     
            // Output the laser scan seq number to the terminal; this isn't the
            // unit test, but merely a helpful means to show what's going on.
            std::cout << "Laser scan sent to LaserScanReceiver with angle_min of: " << laserScan.angle_min << std::endl;
          };
     
          // Extend ILaserScanEndpoint for unit testing needs.
          // May be modified by const functions but maintains logical constness [Meyers, 2005, Item 3].
          mutable int countOfLaserScansPublished;
      };
    }
     
    #endif /* GUARD_LaserScanEndpointStub */

    If you’re paying attention (of course you are!), you’ll notice that this code looks very similar to the code used within the LaserScanReaderTests.cpp class’ fake event handler from Part III. In fact, it’s the exact same code but now it’s encapsulated within a message endpoint stub. Admittedly, this is not a very good testing endpoint (since it won’t make it easier to verify that the laser scans have been “published” via testing asserts), but it does provide an easy means to visually note, while the tests are running, how the message endpoint stub is behaving. More importantly, seeing the laser scans output to the screen will show the application service layer is interacting with the message endpoint appropriately…which is exactly what we’re trying to verify.

    While the LaserScanEndpointStub class could have been coded inline within the unit test class (discussed next), encapsulating it within an external class allows the stub to be reused by other tests as well. This may not be necessary in all cases – in which coding it inline would be just fine – but I typically find myself reusing stubs and mocks to avoid duplicated code in my testing layer; besides, keeping it within an external test double keeps the code arguably cleaner.

  2. Create /ladar_reporter/test/application_services/LaserScanReportingServiceTests.cpp containing the following testing code:
    // LaserScanReportingServiceTests.cpp
     
    #include <gtest/gtest.h>
    #include "LaserScanEndpointStub.hpp"
    #include "LaserScanReportingService.hpp"
     
    using namespace ladar_reporter_application_services;
    using namespace ladar_reporter_test_message_endpoints_test_doubles;
     
    namespace ladar_reporter_test_application_services
    {
      // Define the unit test to verify ability to leverage the reporting service using the messege endpoint stub
      TEST(LaserScanReportingServiceTests, canStartAndStopLaserScanReportingService) {
        // Establish Context
        boost::shared_ptr<LaserScanEndpointStub> laserScanEndpointStub =
          boost::shared_ptr<LaserScanEndpointStub>(new LaserScanEndpointStub());
        LaserScanReportingService laserScanReportingService(laserScanEndpointStub);
     
        // Act
        laserScanReportingService.beginReporting();
        sleep(2);
        laserScanReportingService.stopReporting();
     
        // Assert
     
        // Since we just ran the reader for 2 seconds, we should expect a few readings.
        // Arguably, this test is a bit light but makes sure laser scans are being pushed 
        // to the message endpoint for publication.
        EXPECT_TRUE(laserScanEndpointStub->countOfLaserScansPublished > 0 &&
          laserScanEndpointStub->countOfLaserScansPublished <= 10);
      }
    }
  3. Open /ladar_reporter/test/CMakeLists.txt. Modify the contents to reflect the following:
    include_directories(
      "message_endpoints/test_doubles"
    )
    
    rosbuild_add_executable(
      ladar_reporter_tests
      TestRunner.cpp
      ./core/LaserScanReaderTests.cpp
      ./application_services/LaserScanReportingServiceTests.cpp
    )
    
    rosbuild_add_gtest_build_flags(ladar_reporter_tests)
    
    # Link the libraries
    target_link_libraries(
      ladar_reporter_tests
      ladar_reporter_application_services
      # Important that core comes after application_services due to direction of dependencies
      ladar_reporter_core
    )
  4. With everything in place, head back to the terminal and run:
    make
    cd bin
    ./ladar_reporter_tests

While running the tests, you should see a few messages published to the message endpoint stub. This demonstrates that all of the interactions among our core and application service layers are occurring exactly as expected. Now for the fun part…

In Part V, we’ll finally take a look at using all of these pieces together in order to publish messages to a ROS topic via a message endpoint.

Enjoy!
Billy McCafferty

Download the source for this article.

Part III:  Developing and Testing the Domain Layer

[Author's note, July 28, 2010: Fixed minor bug in LaserScanReader.cpp wherein it couldn't be restarted after being stopped; had to reset _stopRequested to false.]

In Part II of this series, we created the humble beginnings of the package and added folders to accommodate all of the layers of our end product, a well-designed ROS package that reports (fake) laser scan reports.  In this post, the domain layer of the package will be fleshed out along with unit tests to verify the model and functionality, accordingly.  The entire focus will be on implementing just one of the requirements initially described in Part I:  The package will read laser reports coming from a laser range-finder. If you’d like to download the resulting source for this article, click here.

That certainly sounds easy enough.  Disregarding the previous discussions concerning architecture, the gut reaction might be to start adding code to main(), simply taking the results from the range-finder, turning them directly into a ROS message, and publishing the messages to the appropriate ROS topic.  This myopic “get ‘er done” approach quickly gets out of hand as main() turns into a tangled mess of code managing a variety of responsibilities.  Object oriented principles aside, having all of these separate concerns mashed into main turns the little package into a maintenance nightmare with little ability to reuse code.  As mentioned, the first concern that we’ll want to tackle is the ability to read laser range-finder reports.  We’ll tackle this requirement by encapsulating the range-finder integration code within a class called LaserScanReader.cpp.  By doing so, all of the communications to the range-finder are properly encapsulated within one or more classes, making the integration code easier to reuse and maintain.  To keep our focus on the overall architecture, and to avoid the need to have a physical range-finder handy, we’ll simulate range-finder communications within LaserScanReader.cpp.  Certainly an added benefit of this approach, if we were doing this for a real-world package, is that one group could work on the “rest” of the package while another group works on the actually range-finder communications; so when ready, LaserScanReader.cpp could be switched out with the “real” range-finder integration code.

Prerequisites:

Before proceeding, recall that, as described in Part I, the domain layer of the package should not have knowledge concerning how to communicate with the messaging middleware directly (e.g., ROS).  This implies that the domain layer should have no direct dependencies on the messaging middleware.  This allows the domain layer to be more easily reused with another messaging middleware solution.  Additionally, keeping this clean separation of concerns facilitates the testing of the domain layer independently from its interactions with the messaging middleware.  Accordingly, the simple domain layer developed in this post will adhere to this guidance along with full testing for verification of capabilities as well.

Our LaserScanReader class will expose two methods, beginReading() and stopReading(), along with an observer hook to provide a call-back to be invoked whenever a new reading is available.  For now, we won’t worry about what exactly will be called back in the completed package, as that’ll be a concern of the application services layer; but we’ll need to prepare for it by including an interface for the laser scan observer.

Target Class Diagram

The following diagram shows what the package will look like after completing the steps in this post. While the individual elements will be discussed in more detail; the class diagram should serve as a good bird’s eye view of the current objectives.

1. Setup the Package Skeleton

If not done already, follow the steps in Part II to create the beginnings of the package.

2. Create the ILaserScanListener Observer Header

Whenever a laser scan is read, it’ll need to be given to whomever is interested in it. It should not be the responsibility of the laser scan reader to predict who will want the laser scans. Accordingly, an observer interface should be introduced which the laser scan reader will communicate through to raise laser scan events to an arbitrary number of listeners.

Add a new interface header file to /ladar_reporter/src/core called ILaserScanListener.hpp containing the following code:

// ILaserScanListener.hpp
 
#ifndef GUARD_ILaserScanListener
#define GUARD_ILaserScanListener
 
#include "sensor_msgs/LaserScan.h"
 
namespace ladar_reporter_core
{
  class ILaserScanListener
  {
    public:
      // Virtual destructor to pass pointer ownership without exposing base class [Meyers, 2005, Item 7]
      virtual ~ILaserScanListener() {}
      virtual void onLaserScanAvailableEvent(const sensor_msgs::LaserScan& laserScan) const = 0;
  };
}
 
#endif /* GUARD_ILaserScanListener */

As you can see, this C++ interface (or as close as you can get to an interface in C++) simply exposes a single function to handle laser scan events.

3.  Create the LaserScanReader Header

Add a new class header file to /ladar_reporter/src/core called LaserScanReader.hpp containing the following code, which we’ll discuss in detail below.

// LaserScanReader.hpp
 
#ifndef GUARD_LaserScanReader
#define GUARD_LaserScanReader
 
#include <pthread.h>
#include <vector>
#include "sensor_msgs/LaserScan.h"
#include "ILaserScanListener.hpp"
 
namespace ladar_reporter_core
{
  class LaserScanReader
  {
    public:
      LaserScanReader();
 
      void beginReading();
      void stopReading();
 
      // Provides a call-back mechanism for objects interested in receiving scans
      void attach(ILaserScanListener& laserScanListener);
 
    private:
      void readLaserScans();
      void notifyLaserScanListeners(const sensor_msgs::LaserScan& laserScan);
 
      std::vector<ILaserScanListener*> _laserScanListeners;
 
      // Basic threading support as suggested by Jeremy Friesner at
      // http://stackoverflow.com/questions/1151582/pthread-function-from-a-class
      volatile bool _stopRequested;
      volatile bool _running;
      pthread_t _thread;
      static void * readLaserScansFunction(void * This) {
        ((LaserScanReader *)This)->readLaserScans();
        return 0;
      }
  };
}
 
#endif /* GUARD_LaserScanReader */

Let’s now review the more interesting parts of the header class:

  • Lines 3-4:  Standard header guard so that the class is not declared multiple times.
  • Line 8:  Include the laser scan message from ROS.  As discussed previously, the domain layer should not have any direct dependencies on the messaging infrastructure.  The question here is whether or not the domain layer’s knowledge of the laser scan message class violates this principle.  When I initially developed this example code, I wrote a domain-specific equivalent of the laser scan message, placed within /core, so as to avoid any direct dependencies on anything ROS related.  Continuing in this vein, it would then be required that the message endpoint contain a message translator to  convert the domain-specific laser scan class into the corresponding ROS laser scan message, for subsequent publication to ROS.  The motivation for taking this “theoretically pure” approach was to reduce coupling between the domain layer and the messaging infrastructure; one of the advantages being to enable the ability to swap out the messaging infrastructure with another messaging option while having no impact on the domain layer of the package.
    With that said, ROS makes available a very well organized model which is useful to the domain beyond the concerns of messaging itself.  For example, our laser scan reader class is only concerned with  reading information from the laser scanning device (e.g., Sick LMS111 or Hokuyo URG-04LX-UG01) and raising the laser scan event data.  Accordingly, regardless of the chosen messaging infrasturcture, the laser reader ultimately needs to encapsulate the laser scan information within a class for intra-package data passing.  The reader could use a custom (domain-specific) class to encapsulate this information, but we’d end up replicating many of the ROS message classes along with an equivalent number of message translators, without much decoupling benefit.  To illustrate, in the unlikely event that the ROS messaging infrastructure needed to be swapped out with another messaging solution, the domain layer could continue using the strongly typed ROS message classes in the domain, using message translator within the message endpoints, to translate between the ROS message classes (and other domain-specific classes we may be using) with the messages required by the messaging infrastructure.  If ROS messages were not strongly typed, being a collection of name/value pairs instead, for example, then I would avoid referencing ROS message classes from within the domain layer.
    So in our example package here, we will slightly ease the rule of strict domain-layer/ROS decoupling and allow the use of ROS message classes from within the domain layer while still avoiding the introduction of any ROS communication details to the domain, such as how to publish to a topic.  This theoretical vs. practical compromise is a discussion that should be had with any project team to carefully decide how strictly decoupling should be enforced on a given package and specifically where the rule may be eased, if and when appropriate.  In this case, the benefits of using the strongly typed ROS message classes were weighed against the introduction of domain-layer coupling to those classes, accordingly.  Keep in mind that any introduction of coupling with the messaging infrastructure should be carefully reviewed, and well justified, before doing so.
  • Lines 18-19:  Declare the methods beginReading() and stopReading() which will provide the ability to start and stop the reader, respectively.
  • Line 22:  Provide a means for laser scan listeners (observers) to register to receive laser scan reports when available.
  • Line 25:  The readLaserScans() function actually does the work of reading laser reports from the laser scanner and raising the laser data events.  We’ll see in the implementation that it’ll be invoked within the beginReading() function.
  • Line 26: notifyLaserScanListeners() has the responsibility of informing all laser scan listeners that a new laser scan is available.
  • Line 28: _laserScanListeners will hold a reference to every laser scan listerner.
  • Lines 32-38:  These members will facilitate the ability to read and raise laser scan events asynchronously. (As a side note, I spent an abhorrent amount of time trying to get Boost::Thread and Boost::signals2 in place for the threading and callback mechanisms within the ROS context. While I got it working most of the time, the intermittent segfault finally made me throw in the towel in favor of pthreads and observer pattern; more on this below.)

4.  Create the LaserScanReader Class Implementation

Add a new class file to /ladar_reporter/src/core called LaserScanReader.cpp containing the following code, which we’ll discuss in detail below.

// LaserScanReader.cpp
 
#include "LaserScanReader.hpp"
 
namespace ladar_reporter_core
{
  LaserScanReader::LaserScanReader()
    : _stopRequested(false), _running(false) {
    _laserScanListeners.reserve(1);
  }
 
  void LaserScanReader::attach(ILaserScanListener& laserScanListener) {
    _laserScanListeners.push_back(&laserScanListener);
  }
 
  void LaserScanReader::beginReading() {
    if (! _running) {
      _running = true;
      _stopRequested = false;
      // Spawn async thread for reading laser scans
      pthread_create(&_thread, 0, readLaserScansFunction, this);
    }
  }
 
  void LaserScanReader::stopReading() {
    if (_running) {
      _running = false;
      _stopRequested = true;
      // Wait to return until _thread has completed
      pthread_join(_thread, 0);
    }
  }
 
  void LaserScanReader::readLaserScans() {
    int i = 0;
 
    while (! _stopRequested) {
      sensor_msgs::LaserScan laserScan;
      // Just set the angle_min to include some data
      laserScan.angle_min = ++i;
      notifyLaserScanListeners(laserScan);
      sleep(1);
    }
  }
 
  void LaserScanReader::notifyLaserScanListeners(const sensor_msgs::LaserScan& laserScan) {
    for (int i= 0; i < _laserScanListeners.size(); i++) {
        _laserScanListeners[i]->onLaserScanAvailableEvent(laserScan);
    }
  }
}

Let’s now review the more interesting parts of the class implementation:

  • LaserScanReader constructor:  The constructor for the LaserScanReader class initializes the _stopRequested member to false.  Since the reading of laser scans will be performed asynchronously, this private member acts as a poor man’s state machine, facilitating a means to stop the reading of laser scans if set to true. In addition to this, the constructor reserves a wee bit of expected space to avoid too much space being allocated upon the first add to the vector.
  • beginReading():  This function will be called to begin the process of reading laser scans from the laser range finder.  The first step of this process sets the _stopRequested member to ensure that the readings won’t stop until requested to do so.  Next, a new thread is begun to execute the readLaserScans() function asynchronously.  I spent a very long amount of time researching different approaches for the simple thread management needed in this class; the most simple and stable solution I found was on stackoverflow.com. (Please let me know if you have a simpler, cleaner – and still stable – solution.)
  • stopReading():  This function does not explicitly stop the laser scan reading process.  Instead, it simply sets the _stopRequested member to false to inform the asynchronous reading process to terminate. The pthread_join() function is called to wait until the thread represented by the thread object has completed.
  • readLaserScans():  In a real package, this function would communicate with the physical range finding device, collect data, and raise laser scan information via the onLaserScanAvailableEvent.  In our example code here, we’ll simply create a number of fake laser scan reports as long as the _stopRequested member does not equal true.

    Note again that by using the observer pattern to raise laser scan events to listeners, the implementation code need not be aware of who a priori is listening for laser scans, only that a means exists to raise laser scan events, accordingly.  Arguably, readLaserScans() could publish laser scans directly to ROS topics. But this approach comes with the drawback of tightly coupling the laser scan reading functionality to the ROS messaging system, it violates the Single Responsibility Principle, and it makes it more difficult to do “any other stuff” (whatever that may be) with the laser scans before they’re handed off to ROS for publishing without further cluttering readLaserScans().  As the package evolves, we’ll see that an application services layer will be put in place to coordinate the task of handling the laser scan events and passing the information onto a message endpoint for publication to ROS.

  • notifyLaserScanListeners(): Raises the laser scan to any observers. Be sure to note that this does not publish laser scans to ROS, but only raises them to registered observers within the package.

5.  Add a ROS sensor_msgs Dependency to manifest.xml

Since the code above refers to sensor_msgs::LaserScan, a dependency needs to be added for the package to use this class, accordingly:

  • Under /ladar_reporter, open manifest.xml and add the following line just before the closing </package> tag:
    <depend package="sensor_msgs" />

6.  Configure CMake to Include both the Header and Implementation

With the header and implementation classes completed, we need to make a couple of minor modifications to CMake for their inclusion in the build.

First, open /ladar_reporter/CMakeLists.txt and make the following modifications:

  1. Under the first line, which sets the cmake_minimum_required, add a new line to set the project name:
    project(ladar_reporter)
  2. At the end of the CMake file:
    # Include subdirectories for headers
    include_directories(
      "src/core"
    )
    
    add_subdirectory(src)

In doing so, the LaserScanReader header has been included for consumption by other classes and application layers.  This inclusion has been done in the root CMakeLists.txt as this will make the headers available to the unit tests as well.  For more complex packages, this approach of including the headers in the root CMakeLists.txt, to make them globally accessible, may become a bit messy; it may be more appropriate to put the header inclusions in only the CMakeLists.txt which actually require the respective headers if the package is larger.

At this point, a new CMake file is needed under /ladar_report/src:

  • Create a new CMakeLists.txt under /ladar_reporter/src, containing the following:
    # Include subdirectories with their own CMakeLists.txt
    add_subdirectory(core)

You’ll quickly notice that this CMake file has merely passed the buck of defining class libraries further down the chain.  Accordingly, a CMakeLists.txt will be setup for each of the package layers including application_services, core, message_endpoints, and ui.  All of these layers will be compiled into separate class libraries and, finally, an executable.  Arguably, all of these layers could be combined into a single executable with a single CMakeLists.txt file.  But keeping them in separate class libraries keeps a clean separation of concerns in their respective responsibilities and makes each aspect of our package more easily testable in isolation from the other layers.

Next, in order to create the core class library, a new CMake file is needed under /ladar_reporter/src/core:

  • Create a new CMakeLists.txt under /ladar_reporter/src/core, containing the following:
    # Create the core library
    add_library(
      ladar_reporter_core
      LaserScanReader.cpp
    )

We’re now ready to compile the class library for the “core” layer of the package…

7.  Build the core Class Library

In a terminal window, cd to /ladar_reporter and run make.  The class library should build and link successfully.

Woohoo!  Done, right?  Well, not yet…time to test our new functionality.

8.  Unit Test the LadarScanReader Functionality

So far, you’ve had to simply assume that a successful build means everything is working as expected.  Obviously, when developing a ROS package, we’ll want a bit more reassurance than a successful build to be confident that the developed capabilities are working as expected.  Accordingly, unit tests should be developed to test the functionality; in the case at hand, a unit test will be developed to initialize, begin and stop the laser reading cycle to ensure that it is raising laser scan events as designed.

The standard ROS testing tool is gtest; this is a great choice as gtest is very easy to setup and provides informative output during unit test execution.  To setup and run unit tests for the package, only two elements are needed:  a “test runner” to act as the unit tests’ main and to execute all of the package unit tests, and the unit tests themselves which may be spread out among a variety of folders and classes.  When unit testing, I typically write one unit testing class (a test fixture) per class being tested.  Furthermore, I include one unit test for each public function or behavior of the class being tested.  As for a couple of other unit testing best practices, be sure to keep the unit tests independent from each other – they should be able to be run in isolation without being dependent on the running of other unit tests.  Additionally, each unit test is organized as three stages of the test:  “establish context” wherein the testing context is setup, “act” wherein the desired behavior is invoked, and “assert” wherein the results of the behavior are verified. Finally, no testing code should be added to the “production” source code itself; all tests should be maintained in a separate executable to keep a clean separation of concerns between application code and tests.  We’ll see an example of this as we proceed.

  1. To begin testing the laser scan reader, first define the test runner by creating /ladar_reporter/test/TestRunner.cpp containing the following:
    #include <gtest/gtest.h>
     
    // Run all the tests that were declared with TEST()
    int main(int argc, char **argv){
      testing::InitGoogleTest(&argc, argv);
      return RUN_ALL_TESTS();
    }
  2. Now that the unit tests’ main is in place, create /ladar_reporter/test/core/LaserScanReaderTests.cpp containing the following testing code:
    #include <gtest/gtest.h>
    #include "LaserScanReader.hpp"
    #include "ILaserScanListener.hpp"
    #include "sensor_msgs/LaserScan.h"
     
    using namespace ladar_reporter_core;
     
    namespace ladar_reporter_test_core
    {
      // Will be used by unit test to handle laser scans
      struct LaserScanReceiver : public ladar_reporter_core::ILaserScanListener
      {
        LaserScanReceiver()
          : countOfLaserScansReceived(0) { }
     
        mutable int countOfLaserScansReceived;
     
        void onLaserScanAvailableEvent(const sensor_msgs::LaserScan& laserScan) const {
          countOfLaserScansReceived++;
     
          // Output the laser scan seq number to the terminal; this isn't the
          // unit test, but merely a helpful means to show what's going on.
          std::cout << "Laser scan sent to LaserScanReceiver with angle_min of: " << laserScan.angle_min << std::endl;
        }
      };
     
      // Define the unit test to verify ability to start and stop the reader
      TEST(LaserScanReaderTests, canStartAndStopLaserScanReader) {
        // Establish Context
        LaserScanReader laserScanReader;
        LaserScanReceiver laserScanReceiver;
     
        // Wire up the reader to the handler of laser scan reports
        laserScanReader.attach(laserScanReceiver);
     
        // Act
        laserScanReader.beginReading();
        // Let it perform readings for a couple of seconds
        sleep(2);
        laserScanReader.stopReading();
     
        // Assert
     
        // Since we just ran the reader for 2 seconds, we should expect a few readings.
        // Arguably, this test is a bit light but makes sure laser scans are being reported.
        EXPECT_TRUE(laserScanReceiver.countOfLaserScansReceived > 0 &&
          laserScanReceiver.countOfLaserScansReceived <= 10);
      }
    }
  3. Then to include the new test in the build, open /ladar_reporter/CMakeLists.txt and add the following to the end of the file:
    add_subdirectory(test)

    As seen before, this has just passed the buck onto subsequent CMake file(s) to include the appropriate files in the build – which is preferred. Ideally, each CMakeLists.txt should only know about its immediate “surroundings” and not have the concerns of subfolders added to it.

  4. Next, create a new CMakeLists.txt file under /ladar_reporter/test containing the following:
    rosbuild_add_executable(
      ladar_reporter_tests
      TestRunner.cpp
      ./core/LaserScanReaderTests.cpp
    )
    
    rosbuild_add_gtest_build_flags(ladar_reporter_tests)
    
    # Link the libraries
    target_link_libraries(
      ladar_reporter_tests
      ladar_reporter_core
    )

    This CMake file instructs the make process to create a stand-alone gtest executable called ladar_reporter_tests, made up of the two files indicated. (As a side note, ROS has a macro called rosbuild_add_gtest which will include and run the tests automatically when compiled with the command make test. I have reliably encountered segfaults when using Boost asynchronous threading and building with rosbuild_add_gtest. Interestingly, I do not run into such problems if I build and run the testing executable separately from the make process. I have thoroughly researched this topic (i.e., thrown laptops through windows), and have found no solution. Moral of the story: use rosbuild_add_executable to create your test executable.)

  5. With everything in place, head back to the terminal and run:
    make
    cd bin
    ./ladar_reporter_tests

When the test runs, you should see a few laser scan angle_min values get printed to the terminal along with the final report that the test successfully passed.

Now that we’ve done all of the above to complete the core domain layer of the package, let’s review what have was accomplished:

  • Header and implementation classes were developed for communicating with the (fake) laser scan range finder;
  • An observer interface was established to allow (yet unseen) observers listen for new laser scans;
  • A unit test was developed, outside of the package source, to test the reader functionality;
  • CMake was configured to compile the artifacts and to run tests with gtest; and
  • Most importantly, we’ve been able to develop and test our core functionality without needing to involve the ROS messaging system (outside of the use of its LaserScan message class) and without having to prematurely develop any UI layers to test the completed code.

In Part IV, we’ll be setting our sights on developing and testing the application services layer of the application with a test double standing in for the ROS messaging system.

Enjoy!
Billy McCafferty

Download the source for this article.

Part II:  Creating the Package Skeleton

In Part I of this series, we examined the overall architecture that will be put in place with the development of the ROS package.  It’s time to get our hands dirty and put the theory hypothesis to work!  Accordingly, this post in the series will focus on putting together the skeletal package which will contain the various layers of the described architecture. If you’d like to skip to the chase and download the source to this article, click here.

Prerequisites:

If you went through the excellently written ROS tutorials (you did, didn’t you?), you’re no doubt aware that ROS brings with it a number of helpers to make our lives easier.  Accordingly, we’ll start by using roscreate-pkg to create the ROS package itself followed by placeholder folders for the remainder of the package.

  1. Open a terminal and cd to where you’d like your package to reside.  You’ll need to put the package in a folder which is included in the ROS environment variable $ROS_PACKAGE_PATH.  (You can check this setting by running echo $ROS_PACKAGE_PATH at a terminal.)  If your destination folder isn’t defined in $ROS_PACKAGE_PATH (or a sub-folder), you’ll need to add it via /opt/ros/cturtle/setup.sh (e.g., export ROS_PACKAGE_PATH=/opt/ros/cturtle/stacks:/home/username/folder).
  2. Create your package as follows:
    roscreate-pkg ladar_reporter
  3. Verify that ROS can find the package:
    rospack find ladar_reporter
  4. Build the new ROS package:
    rosmake ladar_reporter
  5. Now that the package has been created and building successfully, create a folder structure under the root of the package as follows:
    • src:  Will contain all the source files of the package.
    • src/core:  Will contain the core elements of the package including, and most importantly, the domain layer.  (See Part I for more information concerning the domain layer.)
    • src/core/message_endpoint_interfaces:  Will contain the message endpoint interfaces but not their concrete implementations.  (Consequently, the domain layer will only have knowledge of the message endpoint interfaces, decoupling it from the messaging middleware.)
    • src/application_services:  Will contain the service layer of the package.  In a nutshell, the service layer coordinates the application workflow.
    • src/message_endpoints:  Will contain the concrete classes for communicating with the ROS messaging middleware.
    • src/ui:  Will contain the UI for interacting with the package.  (This layer is not needed on all packages.)
    • test:  Will contain the test classes of our package.
    • test/core:  Will contain tests for classes within src/core.
    • test/application_services:  Will contain tests for classes within src/application_services.
    • test/message_endpoints:  Will contain tests for classes within src/message_endpoints.
    • test/message_endpoints/test_doubles:  Will contain test doubles (stubs to be exact) for testing the application services and domain layer independently from ROS.
  6. If using an IDE (e.g., eclipse), follow any additional directions at http://www.ros.org/wiki/IDEs to make the new project compatible with your IDE.

And with that, the package skeleton is now in place.  Folders have been added to represent all of the application layers that will come to fruition over the next few posts, as we see the package evolve.  (Typically, folders would only be added as needed, but this post provides a concise means to see how the end product will be structured.)

In Part III of this series in developing a well-designed ROS package, the domain elements will be added to the core layer with unit testing, accordingly.

Enjoy!
Billy McCafferty

Download the source for this article.

In previous posts, I discussed general patterns of message-based systems along with basic guidance on developing components for such systems.  While these posts may have provided basic information about their respective topics, there’s a clear difference between theory and implementation.  (The former is easier to fake.)  Accordingly, it’s time to get our hands dirty and provide concrete guidance on developing packages for Robot Operating System (ROS) using proven messaging-system and other developmental design patterns.

This post is the first in a number of posts which walks the reader through nearly every facet of developing a package for ROS.  Primary interests of this series will focus on:

  • Layering a ROS package for maintainability and clean separation of concerns,
  • Making your package as reusable (as practical) to be used with any messaging framework by introducing a clean separation between package concerns and the underlying ROS messaging framework,
  • Using separated interface to easily unit test the elements of your package in isolation of each other and of ROS, and
  • Leveraging proven design patterns to develop a solid package which provides a good balance of theoretical best practices and practical development.

A ROS package is a complete application which happens to send and receive messages via messaging middleware (e.g., ROS) to help it complete its job.  This isn’t too different from an application which simply retrieves and saves data to a database.  Accordingly, the development of the package deserves the same design considerations that a stand-alone application would should receive.  This series of blogs will walk the reader through the development of a package, taking into such considerations, appropriately.  This will be a six part series include:

At the end of this series, the reader should feel comfortable with the concepts behind designing and developing an extensible and maintainable ROS package adhering to proven design patterns and solid coding practices.

A Ladar Reporting Package

Before delving straight into implementation, it’s important to establish the context of the project to assist in guiding architectural and developmental decisions.  Accordingly, the package that will be developed will be a ladar reporting package.  The requirements of the package are simple enough:

  • The package will read laser reports coming from a laser range-finder.
  • Reports acquired from the laser range-finder will be published to a ROS topic as LaserScan messages.
  • The user may start and pause the ladar reporting process via a simple UI front-end.

Our first stop will be in examining the overall architecture of the package in order to conceptualize how the end product will be layered and developed.



Part I:  Planning the Package Architecture

When developing any application, it’s important to strike the appropriate balance between extensibility and maintainability.  We’ve all seen as many “over-architected” solutions as those that did not receive a single thought toward design.  Such applications usually meet their demise in the middle of the night when a wearied developer throws up their hands in debugging exhaustion before starting The (infamous) Rewrite.  Accordingly, when designing a package, “just enough” prefactoring should take place to architect a solution that will smoothly evolve to meet the package’s requirements without over-complicating the solution.  For the task at hand, when architecting a ROS package, there are a number of minimal architectural guidelines which should be adhered to which will lead to a extensible messaging component while being maintainable and easy to understand; a few guiding principles are as follows:

  • A domain layer should exist to encapsulate the core capabilities of the package.  Excellent guidance for developing the domain layer may be found in Eric Evan’s Domain Driven Design.  See Domain Driven Design Quickly for just that.
  • The domain layer of the package should not have knowledge concerning how to communicate with the messaging middleware directly (e.g., ROS).  This implies that the domain layer should have no direct dependencies on the messaging middleware.  This allows the domain layer to be more easily reused with another messaging middleware solution.  Additionally, keeping this clean separation of concerns facilitates the testing of the domain layer independently from its interactions with the messaging middleware.
  • An application services layer should be responsible for managing application “workflow.”  An example is accepting data generated by the domain layer and passing it on to the messaging middleware.  Even then, the application services should only communicate with the messaging middleware (e.g., ROS) via message endpoint interfaces.  Likewise, if the application services need to communicate to a database or other data source, they should do so via data repository interfaces.  This use of separated interface provides the same decoupling benefits as those described for the domain layer.  Admittedly, the application services layer is the trickiest layer to cleanly define the boundry of – it should not contain anything related to the UI (e.g., it should have no references to wxWidgets) nor should it contain any business logic.  A simple way to visualize the responsibilities of the application services layer is to see it as a “task manager.”  I.e., it’s responsible for ensuring that all steps of a given task are completed but is unaware of how to do the work itself; kind of like your manager at work, right?  The execution of the task steps themselves are then carried out by elements of the domain layer and, as we’ll see, the message endpoint concrete implementations.
  • Everything should be independently testable (and tested) from service dependencies.  Accordingly, message endpoints, and other external service dependencies, should be injected into the application services layer via dependency injection.  Doing so facilitates the testing of the application services and domain layers using test doubles.  (To keep things justifiably simpler, we will not be using an IoC container for dependency injection, but manual dependency injection instead.)

At first glance, this may appear to be a lot more than just “minimal prefactoring.”  But after more than a dozen years of professional development, and many painful lessons along the way, I can assure you that this is a solid approach to architecting your package.  With that said, I certainly encourage you and your team to discuss what architectural approach is most appropriate for the task at hand – and the capabilities of the team – before agreeing upon a particular approach.

The best way to further discuss how the architectural guidelines will be implemented in the package, is to review a UML package diagram expressing all of the layers and the direction of dependencies, accordingly:

Keep in mind that this is not a diagram for the overall message-based system; this represents how each individual ROS package is architected.  Accordingly, in the above UML package diagram, each box represents a separate library encapsulating a distinct functional concern.  The arrows represent the direction of dependencies; e.g., application_services depends on core.  Let us now review each layer in more detail, beginning from the bottom up.

Core

As described previously, the domain layer encapsulates the core capabilities of the package.  For instance, if this were a package providing SLAM capabilities, then this layer would contain the associated algorithms and logic.  In addition to domain logic, the core library contains interfaces for services which depend on external resources, such as message endpoints and (if applicable) data repositories.  Having interfaces in the core library allow both core and the application services layers to communicate with services while remaining loosely coupled to the implementation details of those services.

Application Services

As described previously, the application services layer acts as the “task manager” of the application, delegating execution responsibilities to the domain layer and services.  Note that the application services layer, similar to core, has no direct dependency on the service implementation classes, e.g., the message endpoints.  It only has knowledge of the service interfaces for remaining loosely coupled and for facilitating unit testing.

Arguably, in smaller packages and applications, an application services may not add much value and simply complicate an otherwise simpler design.  With that said, care should be taken at the beginning of a project to fully consider the pros and cons of including an application services layer before deciding to discard its use, accordingly.

Data Repositories

If the package were to retrieve and save data to a database or other external data source, data repositories would encapsulate the details of communicating with the external data source.  Note that the data repositories implement the repository interfaces defined in core.

Message Endpoints

This library contains the concrete implementations of the message endpoints.  The message endpoints are the only classes which actually know how to publish, subscribe, and otherwise communicate with the ROS messaging middleware.  Note that the message endpoints implement the endpoint interfaces defined in core.

UI

This layer contains the user interface for interacting with the package, if needed.

Tests

Finally, this library contains all of the unit tests for testing all layers of the ROS package.

This is our package architecture in a nutshell.  In the next post, we’ll begin developing each layer from Core on up to the UI, starting with the overall package structure itself.

Billy McCafferty

Checklist for Developing Message-Based Systems

datePosted on 21:34, March 23rd, 2010 by Billy McCafferty

Even when developing the most basic CRUD application, we ask ourselves a number of questions – whether we realize it or not – during the initial phases of development concerning the architecture and construction of the project.  Where will the data be persisted?  What mechanism will be used to communicate with the database?  How will data from the database be transformed into business objects?  Should separated interfaces and dependency injection be employed to maintain a clean separation of concerns between application logic and data access objects?  What UI components will be leveraged to speed development of the UI layer?  When developing message-based systems (see Message-Based Systems for Maintainable, Asynchronous Development for an introduction) it’s immensely helpful to formalize such questions about how the systems will be designed and developed.  Creating a checklist of such items to decide upon, and formalizing answers for the application context, helps to:

  • Standardize how components (applications participating in the message-based system) will communicate with the messaging middleware;
  • Provide architectural guidance throughout project development concerning how components will leverage message end-points;
  • Define the data model that will be used for sending commands and exchanging data among components;
  • Assist new developers on the team with getting up to speed with maintaining and extending the message-based system; and
  • Support consistency (and predictable maintainability) amongst the components of the system.

This post provides an addendum, if you will (I’m sure you will), to Message-Based Systems for Maintainable, Asynchronous Development for complementing the article with a checklist of questions and architectural topics that should be discussed, decided upon, and/or spiked before beginning development of your budding message-based system.  Accordingly, this does not describe a methodology for developing message-based systems, but simply a checklist of topics which should be taken into consideration before development begins.  Many of the checklist items below serve as good starting points for team discussion and for the development of architectural spikes for demonstrating implementation details.

Messaging Middleware

  • What messaging middleware solution will form the background of the message-based system?
  • How are channels addressed in the selected middleware?  (E.g., as a string or as a port number?)
  • How does the nomenclature of the middleware match up to standard elements of message-based systems and design patterns?  E.g., in Robot Operating System (ROS), a channel is called a “topic.”  Likewise, is their middleware specific nomenclature for elements such as component, publisher, subscriber, point-to-point channel, publish/subscribe channel, message, command message, request-reply message, router, message end-point, and other messaging design patterns?
  • What mechanism is available for peeking at messages going over a point-to-point channel?
  • What utilities are available for viewing active channels, publishers, and subscribers?
  • What other tools does the middleware provide for debugging and observing the messaging system?  Will custom utilities need to be developed to autment development and debugging capabilities?

Integration with Messaging Middleware

  • How will message end-points publish a messages?
  • How will message end-points subscribe to a channel for messages?
  • How will message end-points poll a channel?
  • What technique will be used to decouple the component (participating application) from the message end-point when sending a message?  E.g., dependency injection, separated interface, or other?
  • What technique will be used to decouple the component from the message end-point when receiving a message or polling a channel?  E.g., callback, separated interface, or other?
  • Should exceptions raised by the messaging middleware be wrapped in component specific exceptions for looser coupling?  If so, what will be the standard exceptions?  Additionally, how will such exceptions be logged and tracked for debugging; e.g., email alerts, logging, exception message channel?

Channels and Routing

  • What channels will be created and what data type should each channel carry?
  • Will a hierarchical naming strategy be leveraged for naming and organizing channels?  If so, what are the naming conventions for the project?
  • Has an invalid message channel been setup with a logger to capture and record invalid messages?
  • How should a predictive router be implemented, when needed?
  • How should a reactive router (e.g., a message filter) be implemented, when needed?

Message Elements

  • What data elements may the header of a message contain and how should each be specified?  E.g., return address, message expiration, timestamp, origin, format indicator, etc.
  • How should a message identifier and correlation identifier be generated and included in the header?
  • What is the messaging data model supported and/or enforced by the messaging middleware?  E.g., ROS supports http://www.ros.org/wiki/msg.
  • What canonical data model will be used to imbue message content with domain specific semantic meaning?  E.g., JAUS.
  • How will message translators and/or message mappers be leveraged for converting between each component’s domain model and the canonical data model?
  • How will a command, document, event and request-reply message be composed?

Other Topics

  • How will components maintain information that is associated with a correlation identifier?
  • Are there existing components which need to interact with the messaging middleware which cannot be modified?  If so, how will each communicate with the messaging middleware?
  • How will each component participate with the message based system; e.g., as a polling consumer, as an event-driven consumer, as strictly an event publisher, as a combination of these?
  • Should exceptions raised by a component participate in a global exception tracking and debugging mechanism?

As stated previously, this checklist is not intended to provide a methodology for developing message-based systems, but should serve as a good basis to make sure “T’s are crossed and I’s are dotted” when deciding upon the major architectural aspects and development techniques that will be leveraged throughout the development of your (team’s) message-based system.

Enjoy!
Billy McCafferty

Architectural Paradigms of Robotic Control

datePosted on 07:54, March 12th, 2010 by Billy McCafferty

Introduction

While “architecture” is likely one of the least definable terms in software development, it is unavoidably a topic which has one of the greatest impacts on the extensibility and maintainability of an application.  Indeed, a frequent cause of an application re-write is due to the architectural decisions that were made early in the project, or the lack thereof.  Certainly one of the difficulties in instituting proper architectural practices in a project lies in the fact that architectural decisions must carefully be decided at many different levels of project development.  Obviously, the architectural decisions at each level should be made in context of the project requirements in order to facilitate a proper balance of speed of development, scalability of development, and maintainability of the application in the future.

To illustrate, consider a basic eCommerce site vs. a corporate financial management application which integrates with various third party tools.  There are two aspects of architecture which must be carefully considered.  The first is deciding which project contexts will require architectural consideration.  The second is defining the architectural approach to meet the needs of the given project context, and implementing any necessary prefactoring, accordingly.

For a basic eCommerce site, the project contexts requiring architectural consideration would likely include:  appropriate separation between presentation and control, separation between control and the domain, separation between the domain and data access, and appropriate integration with a payment gateway.  Perhaps the active record pattern might be chosen as the data access mechanism.  If inversion of control seems overkill for such a small application, perhaps direct communications to the payment gateway via the domain objects might be chosen as the means of integration.  Accordingly, judicious prefactoring would suggest that an architectural spike be created demonstrating appropriate use of the active record pattern with a selected tool along with an example of how and where integration with the payment gateway would take place.

For the more complex and demanding needs of the financial management application, architecture considerations, in addition to those taken into account for the basic eCommerce site, might include:  what integration patterns might be leveraged to facilitate client integration, messaging patterns that might facilitate server side integration with third party financial calculators, and where inversion of control is appropriate.  Perhaps RESTful services would be included to provide integration support for clients requiring such capabilities.  Messaging via a publish/subscribe mechanism using a composed message processor might be selected as the ideal means for coordinating data with third party vendors on the server side.  Again, proper refactoring, from an architectural perspective would include developing architectural spikes along with the foundational pieces of such an application to provide appropriate guidance for developers assisting with the project.

Developing software for robotics is no different, in this respect, than developing any other application.  One must decide where the key architectural decisions need to be made and then provide adequate decisions and guidance to facilitate development in accordance with those decisions.  As stated, these decisions must be made in consideration of the project needs.  This post focuses on one project context, the architectural context of determining the overall approach to robotic motor control.  We’ll delve into three major architectural approaches to motor control along with highlighting a few specific implementations.

Deliberative vs. Reactive Robotics

Certainly the best source of intelligent systems to study and emulate are those found in nature.  From the humble ant to the exalted human, evolution has honed a variety of strategies for dealing with the physical world.  Accordingly, if we are to create intelligent systems, a good place to start is by emulating the behaviors and responses to stimuli demonstrated by living creatures.

In the early days of robotics, it was presumed that the most effective approach to emulating intelligence was by taking in detailed measurements provided by sensors, creating an internal representation of the world (e.g., grid-based maps), making plans based on that internal representation, and sending pre-planned commands to actuators (devices which convert energy into motion) for moving and interacting with the world.  Inevitable, this approach presumes that the internal representation of the world is highly accurate, that the sensor reading are precise, and that there is enough time to carry out a plan before the world changes.  In other words, this approach is highly deliberative.  Obviously, the world is highly dynamic, sensor readings are sometimes erroneous, and time is sometimes of the essence when interacting with the world.  E.g., you probably wouldn’t want to spend much time creating an internal representation of the world if there’s a Mac truck speeding towards you.

At the other extreme from deliberative is a reactive approach to interacting with the world.  Taking a purely reactive approach does away with plans and internal representations of the world altogether; instead, a reactive approach focuses on using the world as its own model and reacts, accordingly.  Instead of plans, reactive approaches often rely upon finite state machines to modify behavior as the world changes.  Rodney Brooks changed robotics thinking upside down when he introduced this paradigm shift in the 80s.  The robots he and his team produced were much faster in their reaction times, when compared to deliberative robots, and exhibited surprisingly complex behavior, appearing quite intelligent in many scenarios.  But as is any extreme, a purely reactive approach to the world had it’s own drawbacks; its difficulty in managing complex scenarios which demand careful planning is one such example.

The figure above illustrates some of the differences between deliberative and reactive systems.  Adapted from (Arkin, 1998).

While there are certainly pros and cons to either approach, there are some scenarios which are appropriate to one or the other.  While still others may require more of a hybrid approach.  Let’s now take a look at each approach in more detail.

Deliberative/Hierarchical Style

One of the first successful architectural implementations on a mobile robotic platform was the well known robot known as Shakey, created at Stanford University in the 1960s.  Of particular note was the robot’s architecture which was made up of three predominant layers:  a sensing layer, a planning layer, and an execution layer.  Accordingly, as information would be made available by sensors, Shakey would make plans on how to react to the perceived world and send those plans on to the execution layer for low level control of actuators.  This began the architectural paradigm known as sense-plan-act (SPA).  As the SPA approach matured, additional layers were introduced in a hierarchical style, typically all of which having access to a global world model.  The upper layers in the hierarchy would use the world model to make plans reaching into the future.  After plan development completed at the highest levels, the plans would be broken down into smaller commands and passed to lower levels for execution.  Lower layers would then further decompose the commands into more actionable tasks which would ultimately be passed on to actuators at the lowest level.  In a hierarchical approach, the sensing layers participate in keeping the internal representation of the world updated.  Furthermore, to better accommodate dynamic changes to the world environment, lower planning layers may suggest changes to plans based on recent changes to the world model.

The diagram at right roughly illustrates this hierarchical architectural approach.  As should be noted, the sensing layers update the world model while a hierarchy of planning and execution layers formulate plans and breaks those plans down into actionable tasks.  Adapted from (Kortenkamp, 1998).

4D/RCS

The current pinnacle of hierarchical architectures may be found in the reference architecture known as 4D/RCS (4 Dimensional / Real-time Control System).  4D/RCS is the latest version of the RCS reference model architecture for intelligent systems that has been evolving for decades.  With 4D/RCS, six (more or less) layers are defined for creating and decomposing plans into low level action:

  • Unit/Vehicle/Mission Layer:  this layer decomposes the overall plan into actions for individual modules.  Plans are regenerated every 2 hours to account for changes to the world model.
  • Module Layer:  converts actions into tasks to be performed on specific objects and schedules the tasks, accordingly.  Plans are regenerated every 10 minutes.
  • Task Layer:  converts actions on a single object into sequences of moves to carry out the action.  Plans are regenerated every minute.
  • Elemental Layer:  creates plans for each move, avoiding obstacles and collisions.  Plans are regenerated every 5 seconds.
  • Primitive Layer:  determines motion primitives (speed, trajectory) to facilitate smooth movement.  Plans are regenerated every 0.5 second.
  • Servo Layer:  sends servo control commands (velocity, force) to actuators.  Plans are regenerated every 0.05 seconds.

At the heart of each and every layer are one or more 4D/RCS nodes which contain a behavior generation process which accepts commands from the next higher level and issues subgoals to the behavior generation process at lower levels.  Furthermore, each node reports its task execution status up the chain for consideration into further planning.  While plans are being solidified and disseminated, a sensory processing process in each node receives sensory input from lower levels, updates the world model, and collates the sensory data into larger units which it passes on to the next higher level; e.g., points get converted to lines which get converted to surfaces which get converted to objects with each successive rise through the 4D/RCS layers  A visual summary of a 4D/RCS node quickly shows just how complex such a system can become.  But sometimes the demands of a task require a respective amount of sophistication in the architectural approach.   A comprehensive review of the 4D/RCS approach is discussed in (Albus, 2006).

The primary advantage to deliberative, hierarchical approaches such as 4D/RCS is that competent plans for managing complex scenarios can be generated and broken down into smaller chunks for lower levels to execute.  But an obvious disadvantage to this comes in the form of much added complexity to the overall system while penalizing the speed at which the system can react to a changing environment.

Reactive Style

In the 1980s, Rodney Brooks, in an effort to overcome some of the limitations of sense-plan-act that Shakey and other such robots exhibited, introduced the concept of reactive control.  ”Simply put, reactive control is a technique for tightly coupling perception and action, typically in the context of motor behaviors, to produce timely robotic response in dynamic and unstructured worlds.”  (Arkin, 1998).  In other words, by eliminating the reliance on maintaining an internal world model and avoiding large amounts of time generating plans, simple responses can be executed in reaction to specific stimuli, thus exhibiting behavior similar to that of living organisms.  If there was any doubt in what Brooks was trying to imply, he boldly titled one of his works, Planning is Just a Way of Avoiding Figuring Out What to do Next.  This paradigm shift away from planning turned sense-plan-act into a simpler sense-act.

Accordingly, in a sense-act paradigm, the primary focus is in carefully defining behaviors and the environment stimulus which should invoke those behaviors. This focus is deeply rooted in the idea ofbehaviorism; from a behaviorism perspective, behavior is defined in terms of stimulus and response by observing what an organism does.  This approach of developing robotics around such behaviors, unsurprisingly enough, is commonly referred to as Behavior Based Robotics.  By leveraging simple state machines, which we’ll examine below, to define which behaviors are active for a given stimuli, the overall architectural complexity is greatly reduced while giving rise to responsive, seemingly intelligent behaviors.  (The question of whether or not the robot is truly intelligent and/or self-aware is a debate that I’ll leave to others such as Searle and Dennett.)  While the reactive approach took the spotlight for a number of years, and is still very appropriate in some cases, its limitations in managing complex scenarios and performing sophisticated planning indicated that this approach was not the end all panacea for all situations.

The diagram at right clarifies that reactive systems remove planning and deal with sensory input within the context of each behavior.  I.e., “Behavior 1″ has no knowledge of the feedback coming from “Sensor 3.”  Adapted from (Kortenkamp, 1998).

A Design Methodology for Reactive Systems

Due to the simplistic nature of reactive systems, the corresponding design methodology for developing such systems is rather straight-forward (Kortenkamp, 1998):

  1. Choose the tasks to be performed.  E.g., find kitchen.
  2. Break down the tasks in terms of specific motor-behaviors necessary to accomplish each task.  E.g., find wall, follow wall, recognize kitchen.
  3. For each action, find a condition under which each action should be taken.  E.g., wall found.
  4. For each condition, find a set of perceptual measurements that are sufficient to determine the truth of the condition.  E.g., long straight line connected to obstacle.
  5. For each measurement, design a custom sensory process to compute it.  E.g., bumper sensor activated, edge length over threshold found.

When implemented, we find that the defined behaviors can be realized as states within a finite state machine and that found conditions act as the mechanism for changing from one behavior state to another.  What’s missing is an arbitration mechanism to determine which behavior wins out in light of competing conditions.  Let’s briefly look at implementation approaches to reactive systems along with how such arbitration is achieved.

Subsumption & Motor Schemas

A key concern with reactive, behavior based robotics is determining which behavior should take precedence if conditions exist to activate two or more behaviors.  An arbitration mechanism needs to be introduced to resolve such competing situation.  Brooks dealt with this issue by proposing an architecture known as subsumption.  Simply enough, a subsumption architecture still uses a finite state machine to codify behaviors and transitions, but introduces behavioral layers which can provide input to other layers and override behaviors of lower layers.  The advantage is in facilitating more sophisticated behaviors as a sum of “lesser” behaviors.  It’s better understood by reviewing the following example from (Arkin, 1998):

In the example, there are three behavioral layers:  Avoid-Objects, Explore, and Back-Out-of-Tight-Situations.  The Avoid-Objects Layer’s responsibility is to avoid objects by moving away from any perceived obstacles.  The Explore Layer’s responsibility is to cover large areas of space in the absence of obstacles.  The highest level assists the robot in getting out of tight spaces if the lower layers are unable to do so.  Each discrete behavior can invoke transitions to other behaviors and/or provide input or advice to subsequent behaviors based on perceived conditions.  The “trick” of subsumption is that higher levels can suppress commands between lower level behaviors; consequently, higher layers are able to handle more complex scenarios by manipulating lower level behaviors in addition to its own.  To illustrate suppression, note, in the above example that the “Reverse” behavior in the Back-Out-of-Tight-Situations Layer suppresses any commands that the “Forward” behavior is sending to the actuators.  By doing so, complex behaviors may emerge using a number of basic behaviors and a relatively simple architectural approach.

A major challenge in using a subsumption architecture is deciding the appropriate hierarchy of behavioral layers.  In more complex scenarios, it quickly gets sticky deciding which layer should have the right to suppress which other layers.  (Otherwise known as spaghetti-prone.)  Additionally, since the layers have bi-directional dependencies amongst each other, in order to provide input and suppression, changes to layers can have large impacts on other layers, often resulting in shotgun surgery with any change.  Ronald Arkin introduced a subsequent architecture to address these, and other concerns, with an approach known as Motor-Schema based control which does away with arbitrating competing behaviors.  Each active behavior in a Motor-Schema based control system calculates a vector to be carried out by an actuator (e.g., wheels or arm).  Using vector addition, a final vector for each actuator is computed and sent for execution.  With this approach, the output of behaviors is combined instead of arbitrated.  This avoids the need to determine suppression hierarchies and makes a more extensible application, within the limits of behavior based robotics.

Hybrid Style

Most modern architectural approaches to robotics control attempt to combine the planning capabilities of deliberative systems with the responsiveness of reactive systems.  Appropriately enough, this is referred to as a hybrid style.  While the deliberative approach takes a sense-plan-act perspective and the reactive approach follows with plan-act, a hybrid approach typically takes the form of plan, sense-act.  So while the sense-act layers carry out behaviors, the deliberative planning layer can observe the progress of reactive behaviors and suggest direction based on reasoning, planning and problem-solving.  The diagram at right crudely demonstrates this combination of the two approaches.  Adapted from (Kortenkamp, 1998).

Three-Layer Architecture (3T)

James Firby’s thesis proposing Reactive Action Packages (RAPs) (Firby, 1989) provided a solid approach for integrating deliberative planning with reactive behaviors in the form of a three layer architecture.  A multitude of subsequent architectures have emulated a similar approach, coming to be known as 3T architecture.  From Eran Gat’s essay Three Layer Architecture (Kortenkamp, 1998):

Three-layer architectures organize algorithms according to whether they contain no state, contain state reflecting memories about the past, or contain state reflecting predictions about the future.  Stateless sensor-based algorithms inhabit the control component.  Algorithms that contain memory about the past inhabit the sequencer.  Algorithms that make predictions about the future inhabit the deliberator. … In 3T the components are called the skill layer, the sequencing layer, and the planning [deliberative] layer.

As implied by being a hybrid approach, this 3T architecture is not mutually exclusive to behavior driven robotics.  Indeed, the skill layer itself is made up of unique behaviors which resemble that of reactive systems.  The sequencing layer then uses the world model to determine when a change in behavior is required.  The planning layer can then monitor the lower layers and perform more deliberative, time consuming processes such as path planning.  The primary variation amongst 3T implementations lies in the decision between whether the planning layer “runs the show” or if the sequencing layer takes command and invokes the planning layer only when needed.  Atlantis is one such example that leaves primary control to the sequencing layer to invoke the planning layer.  Other examples of 3T implementations include Bonasso’s Integrating Reaction Plans and Layered Competences through Synchronous Control and Standford’s Junior which took 2nd place in Darpa’s Urban Challenge.

Wrapping Up

The intention of this article has been to provide an introductory overview of paradigms of robotic control including deliberative/hierarchical systems, reactive systems, and hybrid systems.  While each approach is appropriate in select contexts, a hybrid architecture is very adaptable for accommodating a large variety of robotic control scenarios with sufficient planning and reactive capabilities.  The interested reader is encouraged to dig further into the references and links provided to learn more about these various approaches and design methodologies for implementation.

In the next post, we will examine messaging strategies to facilitate the communications amongst the layers and components of robotic systems.

Billy McCafferty


References

Albus, J., Madhavan, R., Messina, E.  2006.  Intelligent Vehicle Systems: A 4D/RCS Approach.

Arkin, R.  1998.  Behavior Based Robotics.

Firby, J.  1989.  Adaptive Execution in Complex Dynamic Worlds.

Kortenkamp, D., Bonasso, R., Murphy, R.  1998.  Artificial Intelligence and Mobile Robots.

© 2011-2014 Codai, Inc. All Rights Reserved