mintforpeople / robobo-gazebo-simulator

Repository for Robobo robot simulation in the Gazebo environment.
Apache License 2.0
4 stars 1 forks source link

robobo-gazebo-simulator

Repository for Robobo robot simulation in the Gazebo environment.

Requirements

Installation

The first step is to open a terminal window and create a ROS Workspace:

mkdir –p ~/<workspace_name>/src
cd ~/<workspace_name>
catkin_make

This model uses the original Robobo ROS messages, so it is necessary to clone the Robobo simulator repositories (model and messages) in your own workspace:

cd ~/<workspace_name>/src
git clone https://github.com/mintforpeople/robobo-gazebo-simulator
git clone https://github.com/mintforpeople/robobo-ros-msgs

Next, you have to clone the Opencv-apps repository because the Robobo ROS messages package depends on it:

git clone https://github.com/ros-perception/opencv_apps

Finally, you have to build the workspace:

cd ~/<workspace_name>
catkin_make

Model launch

You must do the first two steps in each new terminal you need to use the model:

cd ~/<workspace_name>
source devel/setup.bash

To launch the model:

roslaunch robobo_gazebo robobo.launch

You can change the world to load using the parameter world (the parameter is optional, if you don't use it, the test world is loaded):

roslaunch robobo_gazebo robobo.launch world:=small_city_qr

As a consequence, Gazebo will open and the Robobo model will be shown, in a similar way as in the following image (depending on the selected world file):

To control the robot from a Python script, please refer to the video tutorial available at:

https://documentation.theroboboproject.com/gazebo/tutorial_gazebo.mp4

From minute 5:30 onwards, there is a detailed explanation regarding it.

It is important to download the 3D modelled files for the different worlds to work. For this purpose we have created the following repository:

https://github.com/mintforpeople/robobo-gazebo-models

ROS topics

Robobo publishes all its sensors as ROS topics. The current available sensors in simulation are:

It is possible to access the list of topics using:

rostopic list

For instance, to listen the TILT position topic:

rostopic echo /robot/robobo/tilt

Please, refer to the ROS documentation for a detailed explanation of the Robobo sensor topics:

https://github.com/mintforpeople/robobo-programming/wiki/Robobo-Topics

ROS services

In addition, the following actuators are available:

It is possible to access the list of topics using:

rosservice list

For instance, to call the service that moves the wheel motors, we can do the following:

rosservice call /robot/robobo/moveWheels {

lspeed:
  data: 0
rspeed:
  data: 0
time:
  data: 0
unlockid:
  data: 0
error:
  data: 0
}

That we can edit with our specific parameters, for instance:

lspeed:
  data: 20
rspeed:
  data: 20
time:
  data: 2000
unlockid:
  data: 0
error:
  data: 0

}

That will make the Gazebo model move at speed 20 on each wheel during 2 seconds.

Please, refer to the ROS documentation for a detailed explanation of the Robobo actuation services:

https://github.com/mintforpeople/robobo-programming/wiki/Robobo-Services

Simulation configuration

The simulation can be configured in many ways. First, the launch file (https://github.com/mintforpeople/robobo-gazebo-simulator/blob/master/launch/robobo.launch) allows us to set the main configuration parameters of the simulation. Specifically:

To change the simulated world, just modify "test.world" by the name of the world you want to use in the top part of the launch file:

<!--craete a new world-->
    <include file="$(find gazebo_ros)/launch/empty_world.launch">
        <!-- You can change the world name for your own -->
        <arg name="world_name" value="$(find robobo_gazebo)/worlds/test.world"/>
        <arg name="paused" value="false"/>
    </include>

The model description consists of five configurable parameters:

<!--define parameters-->
        <param name="tf_prefix" value="robobo_tf" />
        <arg name="robobo_name" default="robobo"/>
        <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find robobo_gazebo)/urdf/robobo.urdf.xacro' 
            pusher:=true
            camera_front:=true
            emotion:=NORMAL
            visualize_irSensor:=false 
            visualize_camera:=false" />
  1. pusher: determines whether or not the robot carries the pusher piece.
    • Values: false=without pusher, true=with pusher.
  2. _camerafront: Use the front or back camera of the Smartphone.
    • Values: false=front camera, true=back camera.
  3. emotion: changes the Robot's facial expression that is displayed in the Smartphone's screen.
    • Values: HAPPY, SAD, ANGRY, SMYLING, LAUGHTING, EMBARRASSED, SURPRISED, IN_LOVE, NORMAL, SLEEPING, AFRAID and TIRED.
  4. _visualizeirsensor: determines if the infrared sensors are displayed in the gazebo model.
    • Values: true, false.
  5. _visualizecamera: determines if a camera preview is displayed in gazebo.
    • Values: true, false.

Model configuration

The robot model can be configured through the file robobo.urdf.xacro (https://github.com/mintforpeople/robobo-gazebo-simulator/blob/master/urdf/robobo.urdf.xacro) which allows to adapt its response to the specific features of the user's smartphone. Specifically, the following parameters are available (in the same order as shown in the file):

  1. Change the dimensions and mass of the smartphone

  2. Change the size of the camera image and the position on the smartphone.

  3. Change the position and field of view (fov) of the light sensor.

  4. Change the IMU characteristics, position, noise level and offset.

  5. Change the initial battery level of the base and smartphone.

<!--Create tilt-smartphone-->
        <xacro:tilt_link mass="0.2" width="0.0778" length="0.1581" depth="0.0077" emotion_link="$(arg emotion)"/>

        <!--Create camera sensor-->
        <xacro:camera_sensor name="front_camera" width="480" height="640" x="0.1479" y="0.011" z="0" camera="$(arg camera_front)" visualize="$(arg visualize_camera)"/>

        <!--Create light sensor-->
        <xacro:light_sensor x="0.1479" y="0.011" z="0" fov="0.3"/>

        <!--Create IMU sensor-->
        <xacro:IMU_sensor name="IMU" x="0" y="0" z="0" roll="0" pitch="0" yaw="0" noise="0">
            <xyzOffset>0 0 0</xyzOffset>
            <rpyOffset>0 0 0</rpyOffset>
        </xacro:IMU_sensor>

        <!--Define base and smartphone battery charge in percent-->
        <xacro:base_battery initialCharge="90"/>
        <xacro:phone_battery initialCharge="85"/>

Advanced configuration

The file model.urdf.xacro (https://github.com/mintforpeople/robobo-gazebo-simulator/blob/master/urdf/robobo/model.urdf.xacro) contains the xacro:macro code with all the definitions and settings from the previous files. It consists of the following macros:

World configuration

There are several world models created specifically for Robobo, that can be accessed from: https://github.com/mintforpeople/robobo-gazebo-simulator/tree/master/worlds

At this moment, the following worlds are available:

In addition, different objects that can be included in these worlds have been modeled, so the robot can interact with them.

https://github.com/mintforpeople/robobo-gazebo-models

It contains a folder called _models_editormodels. In this folder, all the models are saved in .sdf format, so that later the user can insert them into any gazebo world. To do this, the folder must be copied into the user's folder (/home/user).

When gazebo starts, in the left side menu, press the second tab "Insert". If the models do not appear, click on the "BOX" button, located in the upper menu. Then, create a box and save it in the default folder (model_editor_models). The objects will now appear in the "Insert" tab. To put an object in the world, simply click on it and leave it in the desired position.

Multi robot enviroment

This Gazebo package supports multi robot enviroments. To spawn a Robobo you should add a group tag like the following to the launch file (see here):

    <group ns="NAME*">

        <!--define parameters-->
        <param name="tf_prefix" value="NAME*_tf" />
        <arg name="robobo_name" default="NAME*"/>
        <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find robobo_gazebo)/urdf/robobo.urdf.xacro' 
            pusher:=true
            camera_front:=true
            emotion:=NORMAL
            visualize_irSensor:=false 
            visualize_camera:=false" />

        <!--launch robobo model-->
        <node name="robobo_model" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" args="-urdf -x 0 -y 0 -z 0 -R 0 -P 0 -Y 0  -model $(arg robobo_name) summit -param robot_description"/>

        <!--launch infrared sensors-->
        <node name="robobo_irs" pkg="robobo_gazebo" type="robobo_irs" args="-n $(arg robobo_name)"/>

        <!--launch image node for light sensor-->
        <node name= "image_view" pkg="image_view" type= "image_view" respawn= "false" output ="screen">
            <remap from="image" to="/robot/$(arg robobo_name)/light_sensor/image_raw"/>
            <param name="autosize" value="true"/>
            <param name="image_transport" value="compressed"/>
        </node>
    </group>

Where NAME should be changed to a unique name that will help to identify each specific robot. So each time you want to execute a script that communicates with that Robobo, remember to specify the namespace; ROS allows you to change that using the private variable "_ns".

Example

To launch a example script in multi-robot configuration, in addition to include the robots in the launch file, an appropriate script must be developed.

To launch such script, the following steps should be performed:

cd robobo_ws/
source devel/setup.bash
roslaunch robobo_gazebo robobo_multi.launch

And in a different terminal window:

cd robobo_ws/
source devel/setup.bash
rosrun robobo-multirobot-ros.py

In case you aim to launch the same script in different robots, you can use ROS parameters. For instance, the following command will launch the moveTest.py file (included in the scripts folder) using robobo1 as name for the robot, which will be automatically used in the topic name, avoiding to put it in the launch file. Other three parameters (left speed, righ speed and time) are included too in the command:

rosrun robobo_gazebo moveTest.py __ns:=robot/robobo1 _lspeed:=30 _rspeed:=30 _time:=2000

Structure

This package contains the following folders:

License

robobo-gazebo-simulator is available under the Apache 2.0 license. See the LICENSE file for more info.

Acknowledgement


Empresa subvencionada por el CDTI (Presupuestos Generales del Estado a cargo de la aplicación 27.12.467C.74908) Concretamente, mediante el programa de Ayudas destinadas a nuevos proyectos empresariales de empresas innovadoras (Programa NEOTEC), al amparo de la Orden ECC/1333/2015, de 2 de julio.