Get ACTIVE-IST Open Source Tools at SourceForge.net. Fast, secure and Free Open Source software downloads

JAUS++

Cross-Platform C++ Implementation of the Joint Architecture for Unmanned Systems (JAUS)
JAUS++ Logo

Introduction

The Joint Architecture for Unmanned Systems (JAUS), pronounced "jaws", is an emerging standard for communiction with any type of unmanned vehicle that is independent of the technology employed. JAUS++ is an Open Source (BSD) C++ implementation of JAUS (i.e. JAUS SDK) developed by the ACTIVE Laboratory for use in real and simulated unmanned vehicles. This JAUS SDK is designed to support the rapid development of robotics applications, with the current version implementating the SAE Standard (AS5669, AS5710, AS6009), however previous versions (prior to 2.X) support the complete JAUS Reference Architecture 3.3 message set and Node Manager interfaces. It has been heavily tested, and proven to be compliant with other JAUS implementations at events such as the JAUS Interoperability Challenge. This site contains additional documentation to help users get started with JAUS++ that supplements the extensive examples provided with the library.

JAUS++ Latest Version - SAE-JAUS (AS5669, AS5710, AS6009)

NEWS (04/23/2013): Updated software has been added to the SVN. We have upgraded our Sourceforge project to their latest SVN system, and the latest upload includes bug improvements and parts of AS6060 include Range Sensor service.

NEWS (03/4/2013): Development is still ongoing for JAUS++, with latest code for testing and use within our SVN. We are in the process of adding support for AS6060 (JAUS Environment Sensing Service Set), with basic support for Range Sensors already added. We hope to have a new official release very soon.

NEWS (06/15/2011): JAUS++ used again at the Intelligent Ground Vehicle Competition (IGVC) JAUS Challenge. The Robotics Club at UCF took 2nd place in the challenge, missing 1st place by 2 seconds. The JAUS Challenge requires teams to implement a subset of the JAUS Core and Mobility Service Sets to drive to 4 Local Waypoints comprising a 40 meter route. JAUS++ worked as promised, with the ground vehicle completing the task and winning $3,000.00 in prize money. On another note, we are in the process of getting copies of the latest services releasted by SAE (e.g. Environment Sensing, Mission Spooling) and will begin incorporation for release in version 3.0.

Robotics Club at UCF on the National Mall

NEWS (04/21/2011): JAUS++ and the Robotics Club at UCF were on the National Mall for Robotics Week. We were also mentioned on iheartrobotics.com.

NEWS (02/02/2011): We would like to help make this site a better resource for those new to JAUS and those trying to learn JAUS++. Therefore we will be reviwing some of the tutorial programs and posted new documents that may help. Today was posted some high-level overview slides of the current JAUS standard which can be downloaded here (PDF, PPTX). Please feel free to contact Daniel Barber with any comments, suggestions, or feedback on JAUS++ so we can make it useful to as many people as possible.

NEWS (11/11/2010): New build options, features, and bug fixes have been added to the latest release of JAUS++. CMake is now included as a build option making configuration and installation much simpler for developers. Support for JTCP has also been added, but JUDP is still enabled by default. The transport services have been updated so that JTCP can be used as the communication method between components on the same host, with either JUDP or JTCP being used for inter-node communication via the JTCPClient transport service. Future versions will switch to this mode as the default. Finally, a KeyboardDriver program has been added for users to be able to operate a Primitive Driver service without the need for a joystick.

NEWS (7/30/2010): JAUS++ has been successfully used again for JAUS compliance testing at the recent 2010 Autonomous Underwater Vehicle Competition. In addition to UCF, several other schools used JAUS++ to complete the challenge, including the winning team from Cornell University.

Boatname the Brave

NEWS (6/16/2010): JAUS++ Version 2.X branch is officially compliant with the SAE Standards (AS5669, AS5710, AS6009) after a successful demonstration during the JAUS Interoperability Challenge held at the 2010 Autonomous Surface Vehicle Competition, where the Robotics Club at UCF was the only team able to support all required capabilities. The culminating event was when the JAUS OCP used was able to have the teams boat, "Boatname the Brave," drive to 4 local waypoints on the water. See the example program below on this page to see a test program which demonstrates almost all of the required messages needed for the challenge.


Capabilities

The Open Source (BSD License) JAUS SDK provided by JAUS++ is designed to make it easy for developers to add support for JAUS into their existing projects, or design around the provided architecture framework (Windows and Linux Support). JAUS++ includes complete message libraries for both the Core and Mobility service sets, and interfaces for the most common services (e.g. Discovery, Events, Access Control, Management, Primitive Driver, Global Pose Sensor). JAUS++ is fully object oriented in its design, providing background threads for receiving messages, eliminating the need for developers to add their own sending and receiving loops and threads. It is therefore possible to create a JAUS Component with all the Core Services in less than 10 lines of code.

JAUS++ also includes a few custom/experimental services within the "Extras" library that are not part of the JAUS standard to make it easy to stream video, use a joystick, or interact with a microcontroller. Although these extras are not part of the standard, it is the goal of the authors of JAUS++ to replace these services if they become superceded by new documents released by SAE. In the meantime, these are extremely useful capabilities to take advantage of when developing a robotic system.

Platforms Using JAUS++

As of this writing JAUS++ has been used on multiple simulated and real unmanned systems. At the ACTIVE Laboratory alone we've simulated an Unmanned Ground Systems (UGS) and Unmanned Air System (UAS) in addition to several ground platforms, one of which is the Segway RMP 'P' Series. The Robotics Club at the University of Central Florida also uses JAUS++ on their robotic vehicles (ground, underwater, and surface). The following are a few papers related to projects using JAUS++.

  • Ortiz, E., Barber D., Stevens, J., & Finkelstein, N. "Simulation to assess an unmanned system’s effect on team performance." In Proceedings of the Interservice/Industry Training, Simulation, and Education Conference (I/ITSEC), No.9105, 2009.Orlando, FL: I/ITSEC, 2009.
  • Varcholik, P., Barber, D., Nicholson, D. "Interactions and Training with Unmanned Systems and the Nintendo Wiimote." In the Proceedings of the Interservice/Industry Training, Simulation, and Education Conference (I/ITSEC), 2008.
  • Barber, D., Davis, L., Nicholson, D., Chen, J.Y.C., Finkelstein, N. "The Mixed Initiative Experimental (MIX)Testbed for Human Robot Interactions with Varied Levels of Automation." In the Proceedings of the 26th Army Science Conference, Orlando, 2008.

Getting JAUS++

There are several ways to get our JAUS SDK, one method is to download directly, the other method is to get the latest code via SVN:

Checkout from SVN the ACTIVE-IST Repository:

svn co https://svn.code.sf.net/p/active-ist/code/trunk active-ist

To build only the JAUS++ code, check the box for BUILD_JAUS_ONLY in CMake or use -DBUILD_JAUS_ONLY=True in the command line when generating project files.

System Architecture

The JAUS (and JAUS++) system architecture is, visualized in the image below, is a collection of Subsystems. A Subsystem can be best described as an Unmanned Vehicle (UV) or Operator Control Unit (OCU). Within a Subsystem are Nodes, which are any computing device with a physical address (e.g. computer with Ethernet port, micro-controller with serial connection). Within the Node are Components which provide services. A service is a capability that has been broken down to a point where it is not optimal to break it down further (e.g. Global Pose Sensor, Primitive Driver). Every component within JAUS is given an ID which is composed of the Subsystem, Node, and Component.

System Diagram

Unlike the JAUS Reference Architecture (JAUS RA or JAUS++ 1.5), the ID of the component has no real meaning in regards to capabilities provided. The only requirement as described by the current SAE documents is that if the Component ID is equal to an ID described in the JAUS RA, than that component must only provide the service from that component (e.g. if ID = 38, than it can only support the Core Service set and the Global Pose Sensor service). You can easily avoid this by picking a component ID in the following ranges [1-31] or [60-254].

Services

As described previously, and shown in the above diagram, components are collections of services. The JAUS standard defines services and their interfaces (i.e. messages (command, query, and report) supported. Services do not overlap, and only provide a single set of functionality. Using JAUS++, it is up to you, the developer to add your application specific code into your service implementations. For example, if you are adding support for the Global Pose Sensor service, then you must add in your own code to talk to a GPS or Compass, converting that data into a format the JAUS++ interfaces (or messages) support. The following diagram shows the class inheritance diagram for services within JAUS++. It shows the Core Services and a few Mobility Services available.

System Diagram

If you are familiar with the JAUS standard, you can see how the above diagram mimics the service inheritance diagrams included with AS5710 and AS6009, but is slightly different. This difference was a design choice for the C++ implementation, and was done to avoid accidental mistakes when overloading virtual methods in C++ and to ensure that each service implementation is self contained. For example, instead of Discovery directly inheriting from the Events class, it inherits from the Events::Child class. The Events::Child class only contains methods to be overloaded to add support for generation of events, so that your services (like Discovery) do not include unused code. Therefore, when creating your own services, make sure you inherit from the correct interface. There are plenty of examples that demonstrate how to create custom services (like tutorial program #7).

Tutorial and Sample Code

To help new JAUS++ users get familiar with the capabilities of the library and how things are done, a series of tutorial programs have been developed (in addition to a few example/test programs. Click on the following links to view the code examples:

Example Simulation for JAUS Interoperability Challenge 2010

#include <jaus/mobility/sensors/globalposesensor.h>
#include <jaus/mobility/sensors/localposesensor.h>
#include <jaus/mobility/sensors/velocitystatesensor.h>
#include <jaus/mobility/drivers/localwaypointlistdriver.h>
#include <jaus/core/transport/judp.h>
#include <jaus/core/transport/jtcpclient.h>
#include <jaus/core/component.h>
#include <cxutils/keyboard.h>
#include <cxutils/math/cxmath.h>
#include <iostream>
#include <cstring>
#include <cstdio>
#include <cmath>
 
JAUS::UShort gSubsystemID   = 152;    // ID of our subsystem to use.
JAUS::Byte gNodeID          = 1;      // ID of our node to use.
JAUS::Byte gComponentID     = 1;      // ID of the our component.
 
////////////////////////////////////////////////////////////////////////////////////
///
///   \brief Entry point of jaus_challenge_2010.cpp
///
///   This program demonstrates everything required to complete the JAUS
///   Interoperability Challenge for 2010.  In this program a simulated robot
///   is created which can drive to local waypoints.  This program has
///   run against the JAUS Validation Tool (JVT) and the OCP of the
///   JAUS Interopability Challange during the Autonomous Surface Vehicle
///   Competition, passing all requirements.
///
///   All you have to do is integrate on your own robot, providing real
///   sensor values and generating real control of your bot!
///
////////////////////////////////////////////////////////////////////////////////////
int main(int argc, char* argv[])
{
    JAUS::Component component;
 
    //component.AddService(new JAUS::JTCPClient());
 
    // Setting timeout for control to 0 (disables timeout of control).
    // This is done because the JVT and OCP do not query for the timeout period
    // and may not send messages to re-acquire/maintain control within the
    // normal 2 second timeout window.
    component.AccessControlService()->SetTimeoutPeriod(0);
 
    // Add the services we want/need for our component. By
    // default, the component object already has the Core Service set
    // (e.g. Discovery, Events, Access Control, Management).
    // The Discovery service automatically handles finding other JAUS
    // components, so you do not need to generate any Query Messages
    // (e.g. Query Identification) yourself, because Discovery does it
    // for you.
 
    // In this test program, we are making a simulated robot, which
    // requires the following mobility services.
 
    JAUS::GlobalPoseSensor* globalPoseSensor = new JAUS::GlobalPoseSensor();
    globalPoseSensor->SetSensorUpdateRate(25);      // Updates at 25 Hz (used for periodic events).
    component.AddService(globalPoseSensor);
 
    JAUS::LocalPoseSensor* localPoseSensor = new JAUS::LocalPoseSensor();
    localPoseSensor->SetSensorUpdateRate(25);       // Updates at 25 Hz (used for periodic events).
    component.AddService(localPoseSensor);
 
    JAUS::VelocityStateSensor* velocityStateSensor = new JAUS::VelocityStateSensor();
    velocityStateSensor->SetSensorUpdateRate(25);   // Updates at 25 Hz (used for periodic events).
    component.AddService(velocityStateSensor);
 
    // Need a List Manager Service for Local Waypoint List Driver.  You can
    // ignore this service for the Underwater Vehicle Competition.
    component.AddService(new JAUS::ListManager());
    JAUS::LocalWaypointListDriver* localWaypointListDriver = new JAUS::LocalWaypointListDriver();
    component.AddService(localWaypointListDriver);
 
    // Set Vehicle Identification Information.  Available options for the
    // parameters are JAUS::Subsystem::OCU and JAUS::Subsystem::Vehicle.  Since
    // we are not an OCU, we use Vehicle.  Finally, the string represents the type
    // of robot you have (e.g. Segway RMP, XUV).  This is different than the
    // name of your vehicle, but you can use that if you want.  Your subsystem number
    // is your unique identifier.
    component.DiscoveryService()->SetSubsystemIdentification(JAUS::Subsystem::Vehicle,
                                                             "Simulation");
 
    // Initialize component with a given ID.  Remember, you must
    // add all your services before you initialize the component, because you 
    // cannot add them after initialization.  All services will be deleted by
    // the component on program exit.
    if(component.Initialize(JAUS::Address(gSubsystemID, gNodeID, gComponentID)) == false)
    {
        std::cout << "Failed to Initialize Component.\n";
        return 0;
    }
 
    // Set state to Standby since we have initialized OK.
    component.ManagementService()->SetStatus(JAUS::Management::Status::Standby);
 
    // Now that we are initialized, lets create a fixed connection to the
    // JVT for testing.  Since the JVT and the OCP of the JAUS 
    // Interoperability Challenge do not support multicast for Discovery, you
    // must make a direct connection to them.
    JAUS::JTCPClient* transportService = NULL;
    transportService = (JAUS::JTCPClient*)component.TransportService();
    /*
    // Create connection to JAUS Validation Tool (JVT)
    transportService->AddConnection("24.42.140.203", JAUS::Address(90, 1, 1));
    // Create connection to OCP for the JAUS Interoperability Challenge.
    transportService->AddConnection("192.168.1.42", JAUS::Address(42, 1, 1));
    */
 
    // Set an initial global pose.
    JAUS::GlobalPose globalPose;
    globalPose.SetLatitude(32.703356);
    globalPose.SetLongitude(-117.253919);
    globalPose.SetAltitude(300);
    globalPose.SetPositionRMS(0.0);
    globalPose.SetRoll(0.0);
    globalPose.SetPitch(0.0);
    globalPose.SetYaw(CxUtils::CxToRadians(45));
    globalPose.SetAttitudeRMS(0.0);
    globalPose.SetTimeStamp(JAUS::Time::GetUtcTime());
    // Save the data to the service.
    globalPoseSensor->SetGlobalPose(globalPose);
    // You can set local pose data using global pose
    // as it is automatically converted to local pose data for you.
    // How convenient!
    localPoseSensor->SetLocalPose(globalPose);
 
    // Set an initial velocity state.
    JAUS::VelocityState velocityState;
    velocityState.SetVelocityX(0.0);
    velocityState.SetYawRate(0.0);
    velocityState.SetVelocityRMS(0.0);
    velocityState.SetTimeStamp(JAUS::Time::GetUtcTime());
    // Save the data to the service.
    velocityStateSensor->SetVelocityState(velocityState);
 
    JAUS::Time::Stamp printTimeMs = 0;
 
    double timeDiff = 0.33; // Used for simulation of robot physics.
 
    while(CxUtils::GetChar() != 27 && 
          component.ManagementService()->GetStatus() != JAUS::Management::Status::Shutdown)
    {
        double thrust = 25;
        double steering = 0;
 
        // Simulate some simple physics based on 
        // desired thrust and steering 
        // to reach local waypoints.
 
        double linearDistance = timeDiff*thrust*0.025;
        double linearVelocity = linearDistance/timeDiff;
        double rotation = timeDiff*steering*CxUtils::CxToRadians(1);
        double rotationRate = rotation/timeDiff;
        double yaw = globalPose.GetYaw();
 
        JAUS::Point3D localPosChange(linearDistance, 0, 0);        
        localPosChange = localPosChange.Rotate(yaw, JAUS::Point3D::Z);
 
        CxUtils::Wgs worldPositionWgs(globalPose.GetLatitude(),
                                      globalPose.GetLongitude(),
                                      globalPose.GetAltitude());
        CxUtils::Utm worldPositionUtm(worldPositionWgs);
 
        worldPositionUtm.mNorthing += localPosChange.mX;
        worldPositionUtm.mEasting += localPosChange.mY;
        yaw = CxUtils::Orientation::AddToAngle(yaw, rotation);
        // Convert to WGS
        worldPositionWgs << worldPositionUtm;
 
        // Save newly calculated position and orientation.
        globalPose.SetYaw(yaw);
        globalPose.SetLatitude(worldPositionWgs.mLatitude);
        globalPose.SetLongitude(worldPositionWgs.mLongitude);
        globalPose.SetAltitude(worldPositionWgs.mElevation);
        globalPose.SetTimeStamp(JAUS::Time(true));
 
        velocityState.SetVelocityX(linearVelocity);
        velocityState.SetYawRate(rotationRate);
        velocityState.SetTimeStamp(JAUS::Time(true));
 
        // Save global pose information.
        globalPoseSensor->SetGlobalPose(globalPose);
        // The Local Pose Sensor service supports converting
        // global pose data to local pose data.  It automatically
        // calculates offsets and relative changes for you.
        localPoseSensor->SetLocalPose(globalPose);
        // Save velocity state information.
        velocityStateSensor->SetVelocityState(velocityState);
 
        if(JAUS::Time::GetUtcTimeMs() - printTimeMs > 500)
        {
            // Print status of services.
            std::cout << "\n======================================================\n";
            component.AccessControlService()->PrintStatus(); std::cout << std::endl;
            component.ManagementService()->PrintStatus(); std::cout << std::endl;
            globalPoseSensor->PrintStatus(); std::cout << std::endl;
            localPoseSensor->PrintStatus(); std::cout << std::endl;
            velocityStateSensor->PrintStatus(); std::cout << std::endl;
            localWaypointListDriver->PrintStatus();
            printTimeMs = JAUS::Time::GetUtcTimeMs();
        }
 
        // Exit if escape key pressed.
        if(CxUtils::GetChar() == 27)
        {
            break;
        }
 
        CxUtils::SleepMs((unsigned int)(timeDiff*1000.0));
    }
 
    // Don't delete services, they are
    // deleted by the Component class.
 
    // Shutdown any components associated with our subsystem.
    component.Shutdown();
 
    return 0;
}

JAUS Challenge Example Output