Robot3D Tutorial

Installation

Preliminaries

There are two ways of getting the Simulator, you can either install it from packages made by Anne, or download and compile the source code.
Whichever way you choose, to run Robot3D you will need to install Delta3D, which can be done by using Anne's packages:

> sudo add-apt-repository ppa:robot3d-team/ppa-robot3d
> sudo apt-get update
> sudo aptitude install delta3d-apps

Download and installation of Robot3D from packages

The easiest way to obtain Robot3D is to install it using PPA packages. These packages are automatically built by Launchpad from project's repository.

> sudo aptitude install robot3d-dev robot3d-data

This will install header files of the simulation into /usr/include and Robot3D libraries into /usr/lib. The robot3d-data package contains supporting data for simulations. It is installed into /var/lib/robot3d.

You can run the simulator:

GameStart Robot3D

The simulation should start with just a blank blue screen, because we did not set up any configuration files. See this section to configure them.

scr2.png

Installing Robot3D from the source code

To download and compile the simulator from source, we will need several c++ development packages:
If have never programmed in c++ before start by installing the build-essential package:

> sudo apt-get install build-essential

Then install the bazaar version manager and the cmake build tools:

> sudo apt-get install bzr
> sudo apt-get install cmake 
> sudo apt-get install cmake-curses-gui

The Robot3D simulator source is available at Launchpad: https://launchpad.net/robot3d There are several development branches, which are listed in "Code" section.

  • robot3d/devel this branch is reserved for the simulator's developers
  • robot3d/trunk this branch contains the latest stable version of the simulator
  • robot3d/robo3d-data this branch contains supporting data (3D meshes, maps)
  • robot3d/sampleAgent this branch contains an example of how to control a robot

Here is how to get the source code of the simulator in your own branch based on the devel branch. For this we will create a new directory called robot3D_devel_tutorial.

> mkdir robot3d 
> cd robot3d 
> bzr branch lp:robot3d/devel robot3d_devel_tutorial 
> cd robot3d_devel_tutorial

The source code of the simulator are in two main directories src and inc. The schema of both directories is same, but inc contains only header files and src only .cpp files. For example, the header of src/srCore/hal.cpp is located in inc/srCode/hal.h.

The simulator is compiled using cmake tool. This tool automatically detects all the necessary libraries or reports which libraries are missing. We will use a build directory to build the simulator:

>  mkdir build 
> cd build 
> cmake ..

Now, cmake tries to find all necessary libraries, like osg, boost-* and delta3d. If you do not have them, the cmake report it. For example, if a boost_filesystem package is missing, you will see something like:

er1.png

You can install the missing libraries:

> sudo apt-get install libboost-filesystems-dev 
> cmake ..

If everything is ok, you should see this:

ok1.png
  • If you have some libraries installed in different directories (other than /usr/include and /usr/lib), you can tell this to cmake using environment variables CXXFLAGS and LDFLAGS. For example, if YARP is installed in /opt/include and /opt/lib, we have to tell it to cmake
>export CXXFLAGS='-I/usr/local/include' 
>export LDFLAGS=-L/usr/local/lib' 
>cmake ..

The simulator is compiled by:

build> make

After compilation, the file libRobot3D.so is created in build directory. The simulator is installed by:

build> sudo make install

The Robot3D simulator is installed into /usr/include and /usr/lib.

Running the simulator

GameStart Robot3D
  • If you have installed the simulator (from Ubuntu packages or using make install), you should be able to run it from any directory.
  • If the simulator is not installed, you have to run it from the build directory.

The simulator tries to load the config.xml configuration file. First, the simulator looks in the actual directory, then it tries to load ~/.robot3d/config.xml. If you do not have them, the simulation starts just with a blue blank screen.

TODO Robot3d script

Obtaining robot3d-data from the repository

The robot3d/data branch contain the data files necessary for the simulation. We will download them like the robot3d/devel files:

work> bzr branch lp:~robot3d-team/robot3d/robot3d-data robot3d-data

If you download the robot3d-data files from repository, you have to reference them in your config.xml file, otherwise the simulator will try to load /var/lib/robot3d.

How to configure a simulation

To define a scene in the simulator, two files are used:

  • config.xml, it contains the general properties, and a reference to scene.xml file;
  • scene.xml, in which robots, organisms and agents are defined.

Example of config.xml file:

<?xml version="1.0" encoding="iso-8859-1" standalone="no" ?>
 <Application xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="......dataapplication.xsd">
     <Window Name="MyApp" X="30" Y="30" Width="800" Height="600" PixelDepth="24" RefreshRate="60" ShowCursor="0" FullScreen="0" ChangeDisplayResolution="0" />
     <Scene Name="defaultScene" />
     <Camera Name="defaultCam" WindowInstance="MyApp" />
     <View Name="NewView" CameraInstance="defaultCam" SceneInstance="defaultScene"/>
     <Properties>
         <Property Name="System.SimFrameRate">25</Property>
         <Property Name="System.MaxTimeBetweenDraws">0.3</Property>
         <Property Name="System.UseFixedTimeStep">true</Property>
         <Property Name="ScenarioFile">./scene.xml</Property>
         <Property Name="StageProject">/home/vojta/work/robot3d-data/StageProject</Property>
         <Property Name="CEGUIPath">/home/vojta/work/robot3d-data/gui</Property>
         <Property Name="CEGUISchemeFile">/home/vojta/work/robot3d-data/gui/WindowsLook.scheme</Property>
     </Properties>
 </Application>

We have defined several properties:

  • scene is defined in ./scene.xml
  • robot3d-data is in /home/vojta/work/robot3d-data.

You do not have to use StageProject, CEGUIPath and CEGUISchemeFile if data files are installed in /var/lib/robot3d, i.e. if you installed robot3d-data from package.

A simple scene.xml file:

<?xml version="1.0" encoding="UTF-8" standalone="no"?>
  <Scene activateShadows="0" loadDetailedModels="1" map="amphiTheater" CollisionGeometryDetails="0" ConnectorsAsJoints="0" TimeScale="1">
 
  <Agent_Pool>
          <Plugin name="Test" path="src/" libName="sinusAgent" />
  </Agent_Pool>
 
  <Terminal_Pool>
          <Terminal id="S">
              <Robot name="rX" type="RobotKIT2" connected="15"/>
              <Agent name="c" type="Test" parameter="0"/> 
          </Terminal>
  </Terminal_Pool>
  <Organism structure="SBDSBDSBDSBDS" x="17" y="14" z="8" q_x="0" q_y="0" q_z="1" q_w="0.22"/>
  <Component type="Keyboard" parameter="1" name="keyboard"/>
  <Component type="FreeCam" robotToControl="0" name="freeCam" parameter="-40 -10 20"/>
 
  </Scene>

Here, we have defined several things:

  • map amphiTheater is used,
  • an agent called sinusAgent is defined under alias Test. We will refer to it later by using this alias.
  • one terminal robot is created from RobotKIT2 class. The alias of this terminal is S. The agent Test is assigned to this robot.
  • we created an organism from five KIT robots. The organism is created using the string SBDS…BDS. The positions of the organism is defined using x,y,z values and its rotation using quaternion q_x,q_y,q_z,q_w.

Before running the simulation you should place those two files (scene.xml and config.xml) in your ~/.robot3d/ directory. Then you can run the
simulation by typing : "$ Gamstart Robot3D" or "$ robot3d".

If the agent defined in scene.xml cannot be found, the simulation starts, robots are created but do not move.

scr1.png

How to control a robot

In Robot3D, robots are controlled using agents. An agent can be assigned to exactly one robot. An example of an agent can be downloaded at: Robot3D/sampleAgent

This sample agent controls the main hinge of a robot, so it is useful in organism mode. The idea of the controller is to change angle of the hinge according to a sinus function.
We suppose, that Robot3D was installed into /usr/include and /usr/lib. If not, you have to define the location of Robot3D files manually using ccmake.

Here is how to get the source code of the sample agent, and how to compile it:

>cd work 
>work> bzr branch lp:~robot3d-team/robot3d/sampleAgent sampleAgent 
>sampleAgent> cd sampleAgent 
>sampleAgent> mkdir build 
>sampleAgent> cd buid 
>build> cmake .. 
>build> make

The agent can be installed into /usr/lib/robot3d/components/plugins/agents:

build> sudo make install

You can define the association between agents and robots in your scene.xml file.

<?xml version="1.0" encoding="UTF-8" standalone="no"?>
  <Scene activateShadows="0" loadDetailedModels="1" map="NoObstacles2" CollisionGeometryDetails="0" ConnectorsAsJoints="0" TimeScale="0.1">
 
  <Agent_Pool>
    <Plugin name="Test" path="plugins/agents" libName="sampleAgent" />
  </Agent_Pool>
 
  <Terminal_Pool>
    <Terminal id="S">
          <Robot name="rX" type="RobotKIT2" connected="15"/>
        <Agent name="c" type="Test" parameter="0"/> 
    </Terminal>
  </Terminal_Pool>
 <Organism structure="SACS" x="17" y="14" z="2" q_x="0" q_y="0" q_z="1" q_w="0.221611850414619"/>
 <Organism structure="SBDS" x="10" y="5" z="2" q_x="0" q_y="0" q_z="1" q_w="3.05547054753722"/>
 
 <Component type="Keyboard" parameter="1" name="keyboard"/>
 <Component type="FreeCam" robotToControl="0" name="freeCam" parameter="-40 -10 20"/>/>
 
  </Scene>

In the scene file presented above we have define an agent called Test which is loaded from the library called sampleAgent.
This library is located in the file libsampleAgent.so. To be able to use it, simulator has to know the location of this file.
Where the simulator searches for this file depends on the ROBOT3D environment variable.

  • If ROBOT3D is not set, then the simulator searches the file in /usr/lib/robot3d/components. Because we added plugin/agents as path of this library, the simulator tries to load the simulator tries to load /usr/lib/robot3d/components/plugins/agents/libsinusAgent.so.
  • If the ROBOT3D is set, then directory ${ROBOT3D}/plugins/agents is searched for file libsinusAgent.so

Details of SampleAgent

The sample agent is compiled as shared library. Thus, a mechanism of loading the agent into the simulator has to be defined. This is done in src/sample/sampleAgentPlugin.cpp.
sample/h/sampleAgent.h:

 #ifndef SAMPLEAGENT_H_
 #define SAMPLEAGENT_H_
 
 #include <srCore/hal.h>
 
 namespace srCore {
   class Agent;
 }
 
 namespace sampleAgent {
 
 class SampleAgent: public HAL {
 
 public:
     SampleAgent(srCore::Agent& agent, std::string parameter = "");
     ~SampleAgent();
     void onTickMessage();
     void task();
 
 private:
     float phaseShift;                    //of the controller
     float period;                        //of the periodic behaviour in milliseconds
     float precision;                    //of the control
     float upperLimit, lowerLimit;                //range of the hinge
     int firstRun;
 
 };
 
 }
 
 #endif /* SAMPLEAGENT_H_ */

There are two important methods: task() and onTickMessage:

  • task() task is called when the agent is run in a thread. To run the agent in a thread, you have to call the start() method in the agent's constructor.
  • onTickMessage is called by the simulator at every simulation tick, hence the controller does not need to run in a thread, and the

start() method shouldn't be called in the agent's constructor

It is recommended to control a robot in onTickMessage() method. Thus, all the controlling code
should be write in this method.

Example of non-thread agent: sample/src/sampleAgent.cpp:

/** Example of an agent. There are two ways how the controllers are called:
   * 1. controller in separate thread, the means the a loop is executed independently on the simulator. 
   *    this loop is in task() function, which is called if start() is called in constructor. start() turns on the thread.
   *    this can be time consuming on some systems. some sleep functions should be used in task()
   * 2. controller is called in every tick by the simulator. Thus the controller does not run, if the simulator do other thing.
   *    this should be computationally less intensive and also safer.
   *    in this case, the onTickMessage() function is called every simulation tick.
   */
 #include <sampleAgent.h>
 #include <iostream>
 #include <math.h>
 #define MAX(X,Y) (X>Y?X:Y)
 
 namespace sampleAgent {
 
 SampleAgent::SampleAgent(srCore::Agent& agent, std::string parameter) :
         HAL(agent),
         period(3000),
         precision(100),
         upperLimit(1.4),
         lowerLimit(-1.4)
 {
     firstRun = 0;
      phaseShift = atof(parameter.c_str());
     std::cerr << "Sample agent constructor";
 
 }
 
 /** This function is called by the Simulator every simulation tick. If you want to control the robot not in thread, put your
  * stuff here 
  */
 void SampleAgent::onTickMessage() {
 
     // we create sensors, but only for the first time
     if (firstRun == 0) {
         std::cerr << "Turning on IR sensors\n";
         for (unsigned int i=0; i<getNumIRSensors();i++) {
             activateIRSensor(i, true);
         }
         firstRun = 1;
     } else {
         // we read the sensors
         for (unsigned int i=0; i<getNumIRSensors();i++) { 
            unsigned long val;
            getIRSensorValue(i); 
         }
     }
 
     double time = getTime();
     float phase = (int(( (float)(time)/period + phaseShift) * precision) % MAX(1,int(precision))) / precision;
     float range = fabs(upperLimit) + fabs(lowerLimit);
     float center = (upperLimit + lowerLimit) / 2;
     moveActuator(0, sin(2*M_PI*phase) * range/2 + center);
 }
 
 /** this function is called by thread if 'start()' was called before.
   * If you want to control the robot from threaded agent, put your stuff in this function and call start() in constructor.
   */
 void SampleAgent::task() {
 
 }
 
 SampleAgent::~SampleAgent() {
     exit();
 }
 
 }

How to control screwdrivers?

The screwdrivers are available in RobotKIT2. They can be controlled using moveForward(speed) and moveRight(speed) methods.
Here is an example of a controller, which drivers the robot around a rectangle:

/** this just moves forward/bacward the robot - usefull in swarm mode */
void SampleAgent::swarmMove() {
 
    double t = getTime();
 
    t = ((int)lround(t))% 4000;
 
    std::cerr << "Time = " << t << "\n";
 
    if (t < 1000) {
        moveForward(30);
    } else if (t < 2000) {
        moveRight(30);
    } else if (t < 3000) {
        moveForward(-30);
    } else {
        moveRight(-30);
    }
 
}

Now we can call this method from the onTickMessage()

void SampleAgent::onTickMessage() {
    swarmMove();
}

Sending a message

The HAL class provides several functions for sending messages. The functions accept a pointer to void data and its length , so any type of message can be sent. In the following example, we will send a string value using sendRadioMessage(void *, int), where first argument is the pointer to an arbitrary data, and the second parameter is its length.

sendRadioMessage("radio", 6)

The length of the string is 6, because there are 5 letters and the terminating '\0' char.

We can receive using receiveNextRadioMessage(), which returns pointer to Message class.
The functions return NULL if no message was received.

Message *m;
while( (m = receiveNextRadioMessage()) != NULL ) {
    std::cerr <<  "Radio: msg =" <<  (const char *)msg->getData());
}

More complex messages can be also sent, e.g. using structures. For example, we define a structure Msg as:

struct Msg {
    std::string value1;
    double value2;
};

We will send it using sendRadioMessage(void *, int):

Msg m;
m.value1 = std::string("robot");
m.value2 = getTime();
sendRadioMessage(&m, sizeof(Msg));

To receive it, we have to cast the Message * pointer to the Msg *:

Message *m;
while( (m = receiveNextRadioMessage()) != NULL ) {
    Msg *m = (Msg *)msg->getData();
    std::cerr << "Radio message: value1= " << m->value1 << ", value2" << m->value2 << "\n";
}

Connecting to other robots

Each KIT robot has four connectors (A,B,C,D). To connect to another module, robot the robot has to be close the other one. Then, the method connect(side) performs the connection. The side is one of 'A', 'B', 'C' or 'D'. The connect() method can fail, if the robots are not close enough. To check status of the connection, method isConnected(side) can be used. The connect() method can be used to connect both to a single module and to an organism.

Here is an example, with two robots. The 'R' robot is controlled using an agent (called conAgent), the second robot is static. The scene.xml is:

 <Agent_Pool>
    <Plugin name="cagent" path="messageAgent/src" libName="conAgent" />
 </Agent_Pool>
 
 <Terminal_Pool>
    <Terminal id="R">
         <Robot name="rX" type="RobotKIT2" connected="15"/>
         <Agent name="c" type="cagent" parameter="0"/> 
     </Terminal>
     <Terminal id="S">
         <Robot name="rX" type="RobotKIT2" connected="15"/>
     </Terminal>
 </Terminal_Pool>
 
<Organism structure="R" x="15" y="-5" z="2" q_x="0" q_y="0" q_z="1" q_w="0"/>
<Organism structure="S" x="15" y="15" z="2" q_x="0" q_y="0" q_z="1" q_w="0"/>

Here is the onTickMessage() method of the controller:

void ConnectionAgent::onTickMessage()
    const int si = 0;
    if (_counter == 0) {
        activateIRSensor(si,true);
    }
    const double irval = getIRSensorValue(si);
    cerr << "Is connected: " << isConnected('A') << " " << isConnected('B') << " " << isConnected('C') << " " << isConnected('D') << "\n";
    if (irval > 20) {
        moveForward(-20);
    } else if (irval < 22 && irval > 5) {
        moveForward(-5);
    } else {
        moveForward(-1);
        connect('B');
    }
    if (isConnected('B')) {
        moveActuator(0,-M_PI/4);
    }
}

In this example, robot moves backward (using moveForward(-30)) and detects objects (we assume, that other objects are robots) using IR sensor number 0 (sensor index is determined by variable const int si=0).

The following picture shows the schema of IR sensors, connection sides and commands to move the robot in that directions:
// TODO: Upload new picture

Placement of the sensors/LEDs and so on on robotKIT2:
side 'A' aka Front:
IR sensors 0,1
LEDs 0-3
connector 0
the camera will be placed here, as well as the laser.(tbd)

side 'B' aka Right:
IR sensors 2,3
LEDs 4-7
connector 1

side 'C' aka Back:
IR sensors 4,5
LEDs 8-11
connector 2

side 'D' aka Left:
IR sensors 6,7
LEDs 12-15
connector 3

For example, to move robot in direction of 'D', use moveRight with negative parameter (e.g. moveRight(-30)). The IR sensors mounted on side 'D' has indices 6 and 7. We can activate them by:

activateIRSensor(6,true);
activateIRSensor(7,true);

and read their values using:

unsigned long irval6 = getIRSensorValue(6);
unsigned long irval7 = getIRSensorValue(7);

Another example of connecting robot can be found at: https://code.launchpad.net/~danfis/robot3d/connect-agent

FAQ

How to run the simulator?

  • Type GameStart Robot3D. If you have installed the simulator, it can be called from any directory, otherwise you have to run the simulator from the the build directory.
  • You also need a configuration file config.xml in either actual directory or in ~/.robot3d.

What is the difference between threaded and non-threaded agents?

  • the non-threaded controller is called by simulator at every simulation tick. Thus, the controller does not run, until it is called. The user's code should be places into onTickMessage().
  • the threaded controller runs simultaneously with the simulators. Thus there are at least two threads: one for the simulator, and another one for each agents. The problem is, that the threaded controller does not know, when it should set/get/read/write… values from the simulated robots. To decrease its computational burden, a sleep(x) method can be added into task() method. The threaded controller has to call 'start()' in its constructors. The stat() method then creates a new thread, calls task(). The thread is thus running until task() is finished. So, a while(1) {} loop need to be defined in the task()..

It is not recommended to used threaded agents/controllers

How often is onTickMessage() method called from simulator?

  • The method is called after t = 4.48*timeScale / FPS [s], where timeScale is defined in scene.xml and FPS is defined in config.xml. For example, if you have timeScale=1, FPS=25, then the onTickMessage() is called every 4.48*1/25 = 180ms of simulated time.

How to send int array as message?

int *a = new int[10];
for(int i=0;i<10;i++) {
    a[i] = i;
}
sendRadioMessage(a,10*sizeof(int));

Here is the code to receive it:

Message *msg;
while ((msg = receiveNextRadioMessage()) != NULL){
        int *a = (int *)msg->getData();
        for(int i=0;i<10;i++) {
            cerr << "a[" << i << "]=" << a[i] << "\n";
        }
}

How to get position of a robot?

const srVec3 pos = getPosition();
std::cerr << "Pos= " << pos[0] <<  " " << pos[1] << " " << pos[2] << "\n";

I updated to new version of Robot3D and my agents do not work anymore

After updating the Robot3D you have to recompile all your agents.

How to create a video from a simulation ?

  1. create directory screenshots in the directory, from which simulation is run
  2. start simulation
  3. pres 'p' to start saving images from current camera view into the screenshots directory
  4. (optionaly) pres 'p' to stop creating the screenshots

Video can be made e.g. using mencoder.
One-pass method:

mencoder "mf://*.jpg" -mf fps=25 -o test.avi -ovc lavc -lavcopts vcodec=mpeg4

Or using two-pass method:

mencoder "mf://*.jpg" -mf fps=25 -o test.avi -ovc lavc -lavcopts vcodec=mpeg4:vpass=1:vbitrate=2160000:vqmin=3:threads=2
mencoder "mf://*.jpg" -mf fps=25 -o test.avi -ovc lavc -lavcopts vcodec=mpeg4:vpass=2:vbitrate=2160000:vqmin=3:threads=2

How to get string describing the organism?

There is HAL::getOrganismDescription function, which can be called from a controller:

st::string s;
getOrganismDescription('R',s);

fills the variable s with the organism string, where each robot is represented by single R. If the robot is alone, it will return just 'R'. To obtain the organism string where robots are represented by their IDs, use getOrganismDescription(s) which returns something like '0BD1BD2'…

Unless otherwise stated, the content of this page is licensed under Creative Commons Attribution-NonCommercial-ShareAlike 3.0 License