IMAV Competition 2017 Outdoor League Team Description...

10
1 IMAV Competition 2017 Outdoor League Team Description Guilano (Iran) Erfan Jazeb Nikoo, Navid Hadipour Limouei, Sajjad Rahnama Feshkecheh, Mahdi Etemadi, Babak Moradi, Amir Abkhoshk Prof. Hesabi Robotics Research Laboratory, Islamic Azad University of Lahijan Branch, Lahijan, Iran [email protected] Abstract. Guilano team has been working on the development of multicopter robots since 2010. After several years of research on the mentioned field, we managed to reinvent the artificial intelligence of the robot. Some of our achievements in the recent years are, a combination of RC 1 radio and telemetry link and DIY 2 single board with hopping frequency modulation, making an emergency controller, DIY antenna tracker based on received intelligent RF 3 power and GPS raw data, developing mapping algorithms and intelligent behaviors for the robot. Keywords: Multicopter, Robot, Autonomous, Artificial Intelligence, ROS, Image Processing 1. Introduction Guilano team has committed to working on research and development of multicopter robots since 2010 at Professor Hesabi robotic research laboratory of Islamic Azad University of Lahijan Branch. Some of the team achievements are creating quadrotors, hexacopters, bi-fuel drones in different sizes, applications, as well as winning various awards in competitions and exhibitions. Guilano team took part in the indoor league of Iran Open and ranked 4 in the year 2013. It ranked 5 in the outdoor league of Iran open 2017 as well [1]. Guilano team was, indeed, the best technical team of the 2017 Iran open competition.The team goals have changed to making intelligent robots by image processing, improving AI 4 and fundamental research in electronics since 2013. Thus, we have focused on research and development of hardware and software to improve the functionality of robots. The DIY RC radio controller and telemetry, creating an emergency controller, antenna tracker, developing mapping algorithms and the intelligent making of robot behaviors are some instance of the recent projects In this year, Guilano team is willing to create sophisticated robots. Hence, it needs to be experiencing major changes in hardware and software design in order to participate in the outdoor league. Different flight modes have been simulated, tested and implemented according to the competition rules.Therefore, optimized details for body design was obtained to build a hexacopter robot. Electronic circuits designed were due to sensors and essential capabilities. Robot movement controllers were added to subordinate software layers.The noted Software is divided into two major sections. These sections are object detection based on image processing and Artificial Intelligence (AI) so as to develop proper behavior in different situations. In this paper, we explain algorithms and design details completely and clearly. 2. Robot Control Architecture The control system overview is presented in Figure 1. The pixhawk flight controller [2] is used for low-level control like controlling the angular rotations, setting motor outputs and also providing raw data used by the higher 1 Radio Control 2 Do It Yourself 3 Radio frequency 4 Artificial Intelligence

Transcript of IMAV Competition 2017 Outdoor League Team Description...

Page 1: IMAV Competition 2017 Outdoor League Team Description ...erfanjazebnikoo.com/downloads/IMAV2017_Guilano_Outdoor.pdf · and ranked 4 in the year 2013. It ranked 5 in the outdoor league

1

IMAV Competition 2017 – Outdoor League Team Description

Guilano (Iran)

Erfan Jazeb Nikoo, Navid Hadipour Limouei, Sajjad Rahnama Feshkecheh, Mahdi Etemadi, Babak Moradi,

Amir Abkhoshk

Prof. Hesabi Robotics Research Laboratory, Islamic Azad University of Lahijan Branch, Lahijan, Iran

[email protected]

Abstract. Guilano team has been working on the development of multicopter robots

since 2010. After several years of research on the mentioned field, we managed to reinvent

the artificial intelligence of the robot. Some of our achievements in the recent years are, a

combination of RC1 radio and telemetry link and DIY2 single board with hopping frequency

modulation, making an emergency controller, DIY antenna tracker based on received

intelligent RF3 power and GPS raw data, developing mapping algorithms and intelligent

behaviors for the robot.

Keywords: Multicopter, Robot, Autonomous, Artificial Intelligence, ROS, Image Processing

1. Introduction

Guilano team has committed to working on research and development of multicopter robots since 2010 at

Professor Hesabi robotic research laboratory of Islamic Azad University of Lahijan Branch. Some of the team

achievements are creating quadrotors, hexacopters, bi-fuel drones in different sizes, applications, as well as

winning various awards in competitions and exhibitions. Guilano team took part in the indoor league of Iran Open

and ranked 4 in the year 2013. It ranked 5 in the outdoor league of Iran open 2017 as well [1]. Guilano team was,

indeed, the best technical team of the 2017 Iran open competition.The team goals have changed to making

intelligent robots by image processing, improving AI4 and fundamental research in electronics since 2013. Thus,

we have focused on research and development of hardware and software to improve the functionality of robots.

The DIY RC radio controller and telemetry, creating an emergency controller, antenna tracker, developing

mapping algorithms and the intelligent making of robot behaviors are some instance of the recent projects

In this year, Guilano team is willing to create sophisticated robots. Hence, it needs to be experiencing major

changes in hardware and software design in order to participate in the outdoor league. Different flight modes have

been simulated, tested and implemented according to the competition rules.Therefore, optimized details for body

design was obtained to build a hexacopter robot. Electronic circuits designed were due to sensors and essential

capabilities. Robot movement controllers were added to subordinate software layers.The noted Software is divided

into two major sections. These sections are object detection based on image processing and Artificial Intelligence

(AI) so as to develop proper behavior in different situations. In this paper, we explain algorithms and design details

completely and clearly.

2. Robot Control Architecture

The control system overview is presented in Figure 1. The pixhawk flight controller [2] is used for low-level

control like controlling the angular rotations, setting motor outputs and also providing raw data used by the higher

1 Radio Control 2 Do It Yourself 3 Radio frequency 4 Artificial Intelligence

Page 2: IMAV Competition 2017 Outdoor League Team Description ...erfanjazebnikoo.com/downloads/IMAV2017_Guilano_Outdoor.pdf · and ranked 4 in the year 2013. It ranked 5 in the outdoor league

2

level estimation and control. [3] The IMU5 and sonar data is fused by using a nonlinear filter (unscented Kalman

filter [4]) and the estimates are supplied to the controllers that control the vertical and horizontal position of the

hexacopter by sending altitude and throttle set points back to the pixhawk autopilot.

Figure 1: System Overview

PID6 [5] control is explained in and is one of the most fundamental types of control and also the most

frequently implemented in industry. The great strengths of the PID controller are its simple structure and low

requirements on the system model. Pixhawk used the PID controller to take control of the stability of the robot.

Furthermore, a specific ratio is evaluated by the stated equipment for every direction of movement of the aerial

robot. The method of this controller functionality is described below

Figure 2: PID controller schematic

Guilano robot is controlled in the manual and autonomous mode that is described in this paper.

3. Hardware and mechanical features

A multirotor design and configuration are dependent on many parameters such as take-off, weight, endurance,

wind gust resistance, payload, which are selected based on the consumption of the robot. The consumption may

vary for various purposes such as aerial photography, FPV7, security, and so forth.The aforementioned multirotor

is optimized for 30minutes of flight with the 1kg payload attached in a 30km/h wind speed. In addition, Tiger

antigravity brushless motors and 9 Inch propellers are used in the Guilano multirotor.

Figure 3: Guilano hexacopter

5 Inertial measurement unit 6 Proportional Integral Derivative 7 First-person view

Page 3: IMAV Competition 2017 Outdoor League Team Description ...erfanjazebnikoo.com/downloads/IMAV2017_Guilano_Outdoor.pdf · and ranked 4 in the year 2013. It ranked 5 in the outdoor league

3

3.1. Electronics

After years of research, we obtained the fundamental and necessary factors for proper method to implement

and use the equipment. This robot has different dimensions which numerous creativity and innovations can be

seen in most of them.

3.1.1. Flight Controller

Pixhawk is an open-source hardware project aiming to provide high-end autopilot hardware. Pixhawk is an

advanced autopilot which is developed by DIY Drones. It has a powerful processor by 168 MHz Cortex M4F

CPU (256 KB RAM, 2 MB Flash), advanced sensors (3D accelerometer, gyroscope sensor, magnetometer,

barometer) and NuttX real-time operating system.

The emergency controller board in the broached robot is capable of giving a related function to robot needs in

according to different situations by various sensors used in the robot and complete intelligent experience in both

autonomous and manual modes. This helps an autonomous system to provide control for a robot which decreases

the robot unwanted behaviors even in bad weather conditions or when the connection is lost. This board can be

connected directly to the computer.

Figure 4: Pixhawk flight controller

3.1.2. Components and modules

The components used in the above-mentioned robot are external GPS [6], Air Gear 350 brushless motors and

speed controllers [7], emergency controller board and power supply circuit. Some components made by the panel

are RC radio, emergency controller board, and power supply circuit.

3.1.3. Telemetry and RC Radio

While The DIY Guilano RC radio and telemetry system are based on RFM23Bp [8] and ATmega328

microcontroller hardware which can use large UHF Band, The team have made use of the ISM8 frequency of

(433.05 -434.79 MHz).It can send telemetry data and standard PPM9 [9] [10] signals through eight channels. In

other words, we don’t necessarily use the separate telemetry and RC radio.

The advantage of using our design is to avoid using two radio links on different frequencies, and also works

fine along with numerous interferences with sensitive electronic equipment, namely GPS, magnetometer, servo

motors, camera, gimbal, and so forth.

8 Industrial, scientific and medical 9 Pulse-position modulation

Page 4: IMAV Competition 2017 Outdoor League Team Description ...erfanjazebnikoo.com/downloads/IMAV2017_Guilano_Outdoor.pdf · and ranked 4 in the year 2013. It ranked 5 in the outdoor league

4

This system is based on the opensource of the openLRSng project [11] and modified for more bandwidth, Baud

Rate, Binding code, 5 channel selectable frequency hopping, RSSI1 0 Providing, Failsafe and reduction of the

output RF power for local legislation. The following pictures show the PCB1 1 Design and radio used on the Robot.

Figure 5: The DIY Guilano RC radio and telemetry system

The latest version of this radio can send 8 channel PPM signals and data on 57600 air baud rate.The RFM 23Bp

provides the digital RSSI value for the firmware to convert to PWM1 2 output signal. These signals are received

by the microcontroller which integrates the signals with each other and converts them to an analog voltage in

order to be used by ADC1 3 converter. This is the most important feedback for using the robot in radio range. The

Two pieces of firmware for transmitter and receiver are written and loaded to the ground station and the robot

board.

3.1.4. HD video Stream

The Raspberry Pi 3 [12] and a 5-megapixel camera providing HD video are used in Guilano projects. The

raspberry is beneficial because of the H264 encoder hardware which results in a very low latency about 70 ms

which is very appropriate for the real-time image processing and navigation AI software.

The video streams sent to the ground station by UDP network are a port through the Gstreamer. The open

source software is installed on both the raspberry pi and the ground station Linux machine. We used a 0.6 W

2.4MHz Amplifier with a high gain antenna on both the ground station and the robot, for the medium range (about

1000 meters). Moreover, all the local legislation concerning the RF restrictions was taken into consideration in

the project.

Figure 6: Raspberry Pi 3b and camera

1 0 Received signal strength indicator 1 1 Printed circuit board 1 2 Pulse Width Modulation 1 3 Analog-to-Digital Converters

Page 5: IMAV Competition 2017 Outdoor League Team Description ...erfanjazebnikoo.com/downloads/IMAV2017_Guilano_Outdoor.pdf · and ranked 4 in the year 2013. It ranked 5 in the outdoor league

5

3.1.5. Battery

The Battery depends on the main purpose and ideas to design the copter. For a particular instance, the best

option for mini and micro size batteries is two or three cells of Li-Po1 4 battery that would help to diminish the

size and weight, but increase the current consumption as a result of low voltage.

The battery used in this robot is Li-Po, Tattu Gens Ace 10000mAh 25C 4 Cell, which is specifically designed

for multi-rotor robots. These batteries provide high current to fly at high speed in any direction and high endurance

for about 30 minutes. The mentioned batteries are made by vibrant resistant and fire retardant materials, then they

can be used in various conditions. Low weight and vast capacity are two brilliant features of these batteries.

Figure 7: Tattu 10000mAh 4 Cell LiPo battery

3.2. Mechanics

The frame of the mentioned hexacopter is star-shaped and made by wooden material for the central plates. Its

arms are made of aluminum alloy.

3.2.1. Chassis and body

This robot is a hexacopter which is made of six arms and propellers. The largest size of the robot is 77 cm. The

arms are made of aluminum alloy which is common in aerial industries because this alloy has low weight and

density as well as satisfactory solidity. The appearance of upper and lower chassis is circular. The diameter is 180 mm with the thickness of 5mm.

The chassis is made of wood. The upper chassis used to place main board, speed controllers, besides attaching

arms. The lower chassis is used to place batteries, landing gear and arms. Furthermore, this robot uses an H-shaped

landing gear that is used for more stability and safety in landing.

Figure 8: Designed and simulated body in solid work application

1 4 Lithium polymer

Page 6: IMAV Competition 2017 Outdoor League Team Description ...erfanjazebnikoo.com/downloads/IMAV2017_Guilano_Outdoor.pdf · and ranked 4 in the year 2013. It ranked 5 in the outdoor league

6

3.2.2. Driving mechanism

This robot is powered by 6.920KV Air Gear 350 tiger brushless motors with an 800g thrust that uses 9*4.5

inch propellers along with 4 cell Li-Po battery. As a result, the total thrust of the copter is about 4500g that is used

to neutralize the weight of the hexacopter and the unwanted drifting. Hexarotor releases more driving force and

stability in the sky. The total weight of the robot is approximately 1.5kg to benefit from more strength and speed.

When the robot is expected to turn right or left, it goes to the direction by increasing more torque in opposite

motors.

Figure 9: Brushless motors, speed controllers, and propellers

4. Software (Artificial intelligence and high-level control)

The software section divides into Core, Mapping and GUI1 5

applications. GUI is responsible for receiving inputs from the

drone and controlling it, Core responsibility is to receive inputs

from GUI, analyze data and provide proper outputs for the

drone, and The Mapping application is responsible for making

3D maps from coordinates and aerial images.

In this project C++ programming language, OpenCV and

QT libraries are applied. QT5 libraries and ROS packages

along with other libraries respectively used in all applications.

Figure 11: Guilano team AI applications. GUI and Core.

4.1. Artificial intelligence architecture

In the high-level control system, A suitable structure was designed by Guilano panel for multi-agent decision

making. The structure uses concepts, world model, skills, behavior, and communications to make more intelligent

1 5 Graphical user interface

Figure 10: Core application process flowchart

Page 7: IMAV Competition 2017 Outdoor League Team Description ...erfanjazebnikoo.com/downloads/IMAV2017_Guilano_Outdoor.pdf · and ranked 4 in the year 2013. It ranked 5 in the outdoor league

7

decisions.Some intelligent behavioral algorithm including state-based decision were implemented by the panel to

make the right decision during a mission, shape position estimation and flying above a shape by using image

processing data.

This section includes three main units: planning unit, executing unit and knowledge unit. The major task of the

knowledge unit is to collect sensory and vision output data, analyze and convert them to meaningful data which

are the inputs of decision making sections.

The planning unit main task is to make high-level intelligent decisions (commands) like mission decision

maker, releasing Lifebuoy on the victim and so forth. It, furthermore, orchestrates them with other teammate

decisions in the multi-agent situation.This part is also allocated to the general playing strategies of the team

according to mission states and then sends the appropriate commands to executing unit.

In the executing unit, the commands are analyzed to set the main skills. The skills are basic behaviors like take-

off, Land, Change mode, and arm/disarm the robot.

4.2. ROS

Robots Operating System (ROS) [13] is a set of software frameworks for software development of robots. A

set of tools, libraries, and conventions in order to simplify complex behavior of the robot as a powerful robotic

platform. ROS Indigo version is used in this project. ROS package is generally included in mapping, navigation,

object and face recognition, and also movement detection [14]. ROS is deployed by Guilano team, for controlling

and intelligent behavior of the robot.

4.3. Communications

UDP protocol is applied by our team in order to form a link between Core and GUI. Guilano team applies the

example of using UDP protocol, the coordinates obtained by GUI convert to an XML file and send on UDP port

while Core is waiting for a data in this port.

MAVLink [15] is a communication protocol between Flight Control (FC) and Ground Control Station (GCS)

which provides the capability to control robot for the user by sending message packets to FC. MAVLink is a very

compact library in order to manage messages for micro air vehicles. It can pack C-struck by high functionality

serial channels and send them to GCS. This protocol can be used as a communication link in APM, Pixhawk and

PX4 platforms. MAVLink has been being used in this project as a communication protocol between drone and

GCS since we have used Pixhawk in this project.

Mavros [16] is a communication library between FC and ROS system that can receive FC data to be used in

Core. In addition, Mavros is able to connect to the robot and control it with the help of telemetry (for instance,

changing flight modes, controlling servo motors, controlling robot movements).

4.4. Mapping

One of the missions of the competition is mapping along with trajectory. To conduct this mission, open source

codes are used and changed to satisfy the competition necessities. To run this system, only one camera is needed

to be installed under the robot (the camera faces down). The rviz package which is to show ROS output systems

was applied to demonstrate output data. Rviz includes robot movement directions, the map obtained from camera

and objects from image processing.

Page 8: IMAV Competition 2017 Outdoor League Team Description ...erfanjazebnikoo.com/downloads/IMAV2017_Guilano_Outdoor.pdf · and ranked 4 in the year 2013. It ranked 5 in the outdoor league

8

Figure 12: Guilano team 3D mapping and topography application

4.5. Simulator

A simulator is a tool for testing software and simulation of competition environment. Gazebo is a simulation

framework which works alongside ROS here and illustrates the outputs.

A simulator can work with the sensors such as laser scanner, sonar, parachute and so forth, which are not

available just how a real robot does.To find the strengths and weaknesses of the program, it can be tested in a

simulated environment for several times.

Figure 13: 3D Simulator

5. Image processing

Detecting objects is accurately one of the missions of the competition. OpenCV [18] libraries are made use of

in order to detect objects. In the previous projects, we managed to detect shapes like circle, square, triangle,

pentagon, star and so forth. More complex shapes and colors are needed to train for OpenCV. In the last

competition, the team trained the required shapes, for instance, heart and landing sign, to land by providing images

from different angles and training them by OpenCV libraries. This time-consuming process results in an XML

file which is used to detect the target shape.

In addition, we used canny, filtering and rough circle algorithms from OpenCV libraries to detect simple

colored shapes. Another point to mention is that the image processing program works with ROS. In this method,

Page 9: IMAV Competition 2017 Outdoor League Team Description ...erfanjazebnikoo.com/downloads/IMAV2017_Guilano_Outdoor.pdf · and ranked 4 in the year 2013. It ranked 5 in the outdoor league

9

the image is provided by the topics specified for sending image data. It is beneficial because the main program is

separated from the image processing program. The main program is responsible for controlling the robot. If any

issues occur in the image processing program, the main application works without any problems.

Figure 14: Guilano team image processing application

References

[1] "12th RoboCup Iran Open competitions," Qazvin Azad University, 5 04 2017. [Online]. Available:

http://2017.iranopen.ir/.

[2] "Pixhawk flight controller," Pixhawk, [Online]. Available: https://pixhawk.org/.

[3] J. Fogelberg, "Navigation and Autonomous Control of a Hexacopter in Indoor Environments," LUND

University (Department of Automatic Control), pp. 1-81, 2013.

[4] P. Zarchan and H. Musoff, "Fundamentals of Kalman Filtering: A Practical Approach," American

Institute of Aeronautics and Astronautics, Incorporated, vol. 190, p. 664, 2000.

[5] A. M., "PID Control," Control Systems, Robotics, and Automation, vol. II.

[6] "NEO-M8 series," u-blox, [Online]. Available: https://www.u-blox.com/en/product/neo-m8-series.

[7] "AIR GEAR 350," T-motor, [Online]. Available:

http://www.rctigermotor.com/html/2014/Combo_pack_0930/279.html.

[8] "HOPERF RFM23BP 433MHZ 1W DATA TRANSCEIVER FOR RC ROBOTS FPV,"

HobbiesFLY.com, [Online]. Available: http://www.hobbiesfly.com/hoperf-rfm23bp-433mhz-1w-data-

transceiver-for-rc-robots-fpv.html.

[9] K. T. Wong, "Narrowband PPM semi-blind spatial-rake receiver," European Transactions on

Telecommunications, pp. 193-197, 2007.

[10] Y. Fujiwara, "Self-synchronizing pulse position modulation with error tolerance," IEEE Transactions

on Information Theory, p. 5352–5362, 2013.

[11] "openLRSng - The open source RC system," openLRSng.org, [Online]. Available:

https://openlrsng.org/.

[12] R. P. Foundation, "Raspberry Pi 3 Model B," Raspberry Pi Foundation, [Online]. Available:

https://www.raspberrypi.org/products/raspberry-pi-3-model-b/.

Page 10: IMAV Competition 2017 Outdoor League Team Description ...erfanjazebnikoo.com/downloads/IMAV2017_Guilano_Outdoor.pdf · and ranked 4 in the year 2013. It ranked 5 in the outdoor league

10

[13] T. O. S. R. Foundation, "ROS Core Components," The Open Source Robotics Foundation, [Online].

Available: http://www.ros.org/core-components/.

[14] B. G. &. W. D. S. Morgan Quigley, Programming Robots with ROS, O'Reilly Media, 2015.

[15] QGroundControl, "MAVLink Micro Air Vehicle Communication Protocol," QGroundControl,

[Online]. Available: http://qgroundcontrol.org/mavlink/start.

[16] "Mavros," [Online]. Available: https://github.com/mavlink/mavros.

[17] T. O. S. R. Foundation, "Rviz," The Open Source Robotics Foundation, [Online]. Available:

http://wiki.ros.org/rviz.

[18] A. K. Gary Bradski, Learning OpenCV:Computer Vision with the OpenCV Library, O'Reilly Media,

Inc., 2008.