Architecture:Specification of BABEL Modules

From The BABEL Development Site
Previous: Interfaces Next: RPDs


This page contains detailed information about a collection of modules and their role in the control architecture. The complete list of modules available for download is available here.



Layer 1: HAD Modules

All the interfaces are defined in the previous section.


Module (ICE) name Description Implemented Driver Interfaces
HAD_MobileBase_Pioneer Driver for the Pioneer3 DX/AT mobile bases, through a COM serial port and the ARIA library. DRV_ALIASES, DRV_MOBILE_BASE, DRV_IOBOARD, DRV_BATTERY_LEVEL
HAD_MobileBase_Simulator A simulated 2D mobile base. DRV_ALIASES, DRV_IOBOARD, DRV_MOBILE_BASE, DRV_2D_RANGE_SCANNER
HAD_Laser_Sick_USB Driver for the SICK laser range scanner via RS422-USB board. Hw version is JLBC/APR-05. DRV_ALIASES, DRV_2D_RANGE_SCANNER
HAD_Laser_Hokuyo Driver for the HOKUYO laser range scanner via a COM serial port. DRV_ALIASES, DRV_2D_RANGE_SCANNER
HAD_GPS Driver for COM-connected GPSs. DRV_ALIASES, DRV_GPS
HAD_GasSensors Driver for the custom-built e-Noses (Hardware Feb-2007). DRV_ALIASES, DRV_GAS_SENSOR
HAD_IMU_XSens Driver for the XSENS IMU. DRV_ALIASES, DRV_IMU_SENSOR
HAD_Generic_Camera Driver for any OpenCV/FFmpeg/Bumblebee camera (any camera supported by MRPT's CCameraSensor). DRV_ALIASES, DRV_CAMERA_SENSOR



Layer 2: Basic Sensory (BS) Modules

Recall that all these modules share a common IF as described in the previous section.


BS_IncrementalEgoMotion

  • Description: This module collects data from odometry, and possibly from visual odometry, etc... to provide incremental estimations of the robot pose.

Unlike most other modules which starts with sending events disabled by default, BS_IncrementalEgoMotion will always send an event for each new action available.

This module will read odometry from one of these sources (it will automatically detect which module is up):

  • BA_RoboticBase: For 2D wheels odometry.
  • BS_Vision: For stereo vision odometry (Not implemented yet!)

IMPORTANT NOTE: If some module is interested in a detailed list of robot pose increments, it MUST listen for events launched by this module and read all of the increments (see table of events).

  • Interface:
BABEL service group BABEL services to implement

EGO_MOTION

The interface for Ego-Motion measurements.

<cpp>

getAction(

out COMMON::SeqOfBytes act, out boolean error ) </cpp>

Return the last action as a serialized MRPT object of the class mrpt::slam::CAction. This can be a 2D or 3D incremental movement of the robot.

BS_Vision

  • Description: This module collects images from the available cameras and:
    • Provides the raw images, as CObservationImage or CObservationStereoImages objects.
    • Performs real-time feature tracking from stereo images (if available) and provides the tracked landmarks as an object of the class CObservationVisualLandmarks.

BS_RangeSensors

  • Description: This module collects data from laser range scanners, and ultrasonic sensors.





Layer 2: Basic Actuators (BA) Modules

BA_RoboticBase

  • Description: This module implements DRV_MOBILE_BASE and redirects all the calls to the actual underlying device, either a real robot or the simulator.

This is the module to use when one wants the mobile base to move or stop, or one wants to read odometry.

BA_JoystickControl

  • Description: This module reads command from a Joystick and send the motion commands to BA_RoboticBase. It can be enabled/disabled by pushing buttons 0 and 1 simultaneously during a few instants.





Layer 3: Sensory Detector (SD) Modules

SD_PeopleDetector

  • Description: This module detects people around the robot using sensor data from range scanners, images, etc....
  • Interface: Create a new type of observation? and/or add some specific method to retrieve the detected data.


SD_Local3DMap

  • Description: This module maintains a 3D representation of close obstacles around the robot, by fusing data from sonars, laser scanners, and stereo vision. These "instant" maps only represent the very most recent observations, i.e. there is no map-building process apart from a trivial one.
  • Interface:
BABEL service group BABEL services to implement

LOCAL_MAP

The interface for manipulating the local map.

<cpp>

getObstacles2D(

in float min_height, in float max_height, out COMMON::SeqOfFloat obs_x, out COMMON::SeqOfFloat obs_y, out boolean error ) </cpp>

Return the last estimate of 2D obstacles around the robot, only for the heights (z axis) between the given range. Error will be true if no data has been updated for more than a few instants.

<cpp>

enableEvents(

in boolean onNewObservation in boolean onFailure ) </cpp>

Enables (true) or disables (false) sending events on arrival of new measurements or a sensors failure. Default values are all events disabled. The events numeric codes must be unique for each module (see appendix II).





Layer 3: Function Executors (FE) Modules

Recall that all these modules implement the Common Actions Interface.


FE_ReactiveNavigation

Controls the reactive navigation capabilities of the robot in 2D. If a request is received while navigating, the previous one is automatically marked as cancelled.

  • Action: "navigate"
  • Action parameters (text lines within 'params' in the service executeAction(...) ):
    • "target_x = ...": The target location (in meters), X-coordinate in the current sub-map.
    • "target_y = ...": The target location (in meters), Y-coordinate in the current sub-map.
    • "relative = 0 | 1" (OPTIONAL, default=0): If set to "1", (x,y) coordinates are interpreted as relative to the current robot pose.
    • "max_dist = ...": (OPTIONAL) The distance (in meters) to the target location such as navigation can be considered successful.
    • "max_speed = ...": (OPTIONAL) If supplied, indicates the max. speed (m/s) of the robot. Angular max. speed is automatically derived. This can be used in situations known to be dangerous for the robot.
    • "targetAllowedDistance = ...": (OPTIONAL) The distance at which the robot will stop from the target (in meters, default = 0.30)


Example of usage

How to start a reactive navigation from a client module:


<cpp> double targetX = 4.0; double targetY = 5.0;


// ---------- Reactive navigation request ---------- const char *action = "navigate"; unsigned int out_actionId; char *_out_errorReason; std::ostringstream params;

params << "target_x = " << targetX << std::endl; params << "target_y = " << targetY << std::endl;


  1. JMS-INCLUDE(INC_request-synchronous&blocking,"executeAction","FE_ReactiveNavigation","executeAction","REMOTE_FE_ReactiveNavigation_var","action,params.str().c_str(),out_actionId,_out_errorReason","err_var","0","INF","","","")#

const std::string errorReason(_out_errorReason); BABEL::string_free(_out_errorReason);

if (err_var) throw std::logic_error("ERROR calling FE_ReactiveNavigation"); if (!out_actionId) throw std::logic_error( std::string("FE_ReactiveNavigation returned error: ")+errorReason );

// -------------------------------------------------------- </cpp>

FE_DoorOpening

Asks a nearby human to open the door.

  • Action: "openDoor"
  • Action parameters (text lines within 'params' in the service executeAction(...) ):
    • None.







Layers 2/3: Others

The following modules don't fit within either Actuators or Sensors, but they are required by other modules in layers 2,3 or in the higher-layers.


Localization_PF

  • Global localization and pose tracking for a mobile robot using range sensors (lasers/sonars) and a global map. The particle filter will be NOT run unless the robot really moves, in order to prevent particle depletion.
  • Do NOT call this module directly to obtain the current robot pose, but to Localization_Publisher.


BABEL service group BABEL services to implement

LOCALIZATION

The interface for publishing robot localization.

<cpp>

getCurrentPose(

out double x, out double y, out double z, out double yaw, out double pitch, out double roll, out COMMON::TTimeStamp timestamp, out boolean error ) </cpp>

Return the last estimated pose of the robot (just its mean, without covariance), in coordinates relative to the global, static map.



Localization_Publisher

  • This module collects the current localization of the robot from a localization particle filter or any SLAM or HMT-SLAM module and publishes it in a uniform format.


BABEL service group BABEL services to implement

LOCALIZATION

The interface for publishing robot localization.

<cpp>

getCurrentPose(

out double x, out double y, out double z, out double yaw, out double pitch, out double roll, out string submapID, out string submapLabel, out COMMON::TTimeStamp timestamp, out boolean error ) </cpp>

Return the last estimated pose of the robot (just its mean, without covariance), in coordinates relative to the given sub-map.





NavigateLoops

  • This module loads a sequence of "nodes" defined by their global coordinates, and executes a reactive navigation through them in sequence.





A practical example

An example of the low-level control architecture for a 2D robot with 2 laser scanners and a stereo camera:


Example control arch 1.png