An Experimental Testbed for Robotic Network Applications

Size: px
Start display at page:

Download "An Experimental Testbed for Robotic Network Applications"

Transcription

1 An Experimental Testbed for Robotic Network Applications Donato Di Paola, Annalisa Milella, and Grazia Cicirelli Abstract In the last few years, multi-robot systems have augmented their complexity, due to the increased potential of novel sensors and actuators, and in order to satisfy the requirements of the applications they are involved into. For the development and testing of networked robotic systems, experimental testbeds are fundamental in order to verify the effectiveness of robot control methods in real contexts. In this paper, we present our Networked Robot Arena (NRA), which is a software/hardware framework for experimental testing of control and cooperation algorithms in the field of multi-robot systems. The main objective is to provide a user-friendly and flexible testbed that allows researchers and students to easily test their projects in a real-world multi-robot environment. We describe the software and hardware architecture of the NRA system and present an example of multi-mission control of a network of robots to demonstrate the effectiveness of the proposed framework. 1 Introduction In these last years, multi-robot systems are being widely investigated, since they offer better performances than single robot systems in challenging applications, such as exploration of hostile environments, terrain mapping, space and rescue operations [1],[2],[3],[4]. Due to the intrinsic difficulty in developing and assessing the performances of multi-agent control algorithms in real contexts, much work has been carried out only analytically or in simulation [5],[6],[7]. Advanced simulation tools for multi-robot systems have been also developed, and are available as open source tools (e.g., Stage and Gazebo) or as commercial products (e.g., Webots, Microsoft Robotic Studio etc.). Donato Di Paola, Annalisa Milella, Grazia Cicirelli Institute of Intelligent Systems for Automation (ISSIA), National Research Council (CNR), via G.Amendola 122/D, Bari, Italy, {dipaola, milella, grace}@ba.issia.cnr.it 1

2 2 Donato Di Paola, Annalisa Milella, and Grazia Cicirelli Nevertheless, for complete analysis and testing, and to provide additional insights to theory, real world experiments are generally desirable. On the other hand, experimentation in robotics for comparison of different methods is often difficult due to the variety of robotic platforms and environments that may be encountered. Therefore, the development of experimental testbeds is a key issue for the design of effective multi-robot control systems. These testbeds can support all stages of the design process, including algorithm development and testing, conventional simulation, robot-in-the-loop simulation, and real robot control, in an integrated way. An example of platform for conducting, evaluating and analyzing experiments in robotics, named the Teleworkbench, can be found in [8]. In this paper, we describe our experimental set-up, referred to as Networked Robot Arena (NRA) that allows us to monitor, control, and test realistic behaviours of relatively simple multi-robot systems. This set-up includes both hardware and software components. The main contribution of the work is the development of a low cost, robust, flexible, and scalable software/hardware system, which uses desktop mobile robots with a vision-based identification and localization system, and a multi-mission control framework. The control architecture is a hybrid distributed architecture in which the high-level multi-mission control is performed by a software module with a number of controllers, each one in charge of managing a sub-network, while the low-level operations are implemented on board each robot. The proposed framework can serve as a middle ground between a totally software-based simulation tool and a full-scale real-world implementation. From the one hand, it allows one to encompass real-world problems difficult to model and manage in a virtual environment, such as errors in robot identification and localization, or interactions with other objects. On the other hand, it is based on user-friendly and flexible tools, which can be used by both researchers and students to easily test their projects. 2 Overview of the Networked Robot Arena In this section, we provide an overview of the NRA. The main goal of the proposed system is to set up a hardware and software framework to assist the development and testing process of robotic network applications for educational and research purposes. The NRA has the following characteristics, which are typically desired for education and research testbeds: open software and hardware platform; desktop mobile robots; low cost; robust, flexible and scalable software; user friendly software development and maintenance. In order to satisfy these requirements, the NRA features the logical structure shown in Figure 1. The main components of the system are the arena, i.e., the physical environment where the robots operate, and the workstation, i.e., the computer in charge of communicating with the robots and controlling most of software modules.

3 An Experimental Testbed for Robotic Network Applications 3 The arena is a bounded and controlled environment in which the robots, wireless connected, can move to perform the desired tasks. In order to satisfy the small size requirements, in our implementation, the arena is a desk with boundaries and movable objects (i.e., small wooden items), which can be arranged to create walls and divide the environment in different zones. A camera is placed high above the arena to monitor positions and actions of the robots over time. This camera sends images to the workstation for elaboration, through a USB port. The output of the image processing algorithm consists of a set of robot IDs and their positions in the arena, which are fed into the control system of the network. A short-range wireless connection is adopted to link the robot network with the workstation. The latter runs a software architecture, which is in charge of: managing the connections between the workstation and the network of robots, using appropriate communication libraries; processing the images acquired by the overhead camera; controlling the network with high-level decision making algorithms; communicating the control decisions to the robots. Indeed, control is not totally centralized in the control module of the architecture, but it is distributed between the workstation and the network of robots. Furthermore, no a priori knowledge about the environment configuration is required by the control system. In order to facilitate the use of the testbed by researchers and students, MATLAB is employed as software development environment. In the next sections, each part of the system architecture is described in more detail. 2.1 Robots and Hardware Infrastructure As discussed above, two of the design requirements of the NRA are the desktop-size dimensions of the robots and the possibility to have an open hardware platform. Keeping in mind these requirements, we analyzed different solutions. First, we selected three robots as possible candidates for the NRA platform: the K-Team Khepera robot [9], the Lego Mindstorms NXT, and the E-Puck robot. Khepera is Fig. 1: Schematic representation of the Networked Robot Arena (NRA).

4 4 Donato Di Paola, Annalisa Milella, and Grazia Cicirelli a small size robot, which can be equipped with various sensors, like infra-red proximity and ambient light sensors, cameras, and ultrasonic sensors, but it is relatively expensive. The Lego Mindstorms NXT is a modular platform with a rich set of sensors; however, it is not an open platform, and it is not suitable for desktop size robotic networks. Finally, we chose the E-Puck robot (see Figure 2(a)), because of its small size, low cost and open hardware characteristics [10]. The E-puck is a desktop size (7.0 cm diameter) differential wheeled mobile robot. It was originally designed as an education tool for engineering and robotics. It is equipped with a powerful Microchip dspic (i.e., dspic 30F6014A) microcontroller, and the following sensors and actuators: eight infrared (IR) proximity sensors, placed around the body; a 3D accelerometer that can be used to measure the inclination and acceleration of the robot; three microphones, to localize source of sound by triangulation; a CMOS colour camera ( ), mounted in the front of the body; two stepper motors for differential drive; a speaker, connected to the audio module; a set of LEDs placed on the body to provide a visual interface to the user; a set of communication interfaces (i.e., a Bluetooth radio link, a RS232 serial interface, and an infrared remote control receiver). The hardware infrastructure of the NRA testbed consists of a bounded arena (60 cm 110 cm) with a wireless communication network, a USB camera, and a high performance workstation (see Figure 2(b)). The camera consists of a USB colour device, placed at about 150 cm above the arena. It provides robot identity (a) (b) Fig. 2: Robots and Hardware Infrastructure: (a) close up of an E-Puck robot inside our arena; (b) the Networked Robot Arena.

5 An Experimental Testbed for Robotic Network Applications 5 and position information for the control system, and can be also used as groundtruth basis for experimental validation of the algorithms. For the given arena and robot size, an image resolution of is sufficient to detect and track all the robots. The workstation consists of a high performance computer, equipped with an Intel Core 2 vpro microprocessor and 4 Gb RAM, and is used for control, visual data processing, and connection with the network of robots. Since we need short-range communication among the agents, and between the agents and the workstation, we use a Bluetooth wireless network. Due to the small amount of data passed through the network and the hardware and software module embedded within the E-Puck, the Bluetooth communication protocol revealed a good choice. 2.2 Software The main goal of the NRA software architecture is to provide a distributed mission control system, able to manage all the activities of the robotic network. We assume that the network has to execute a number of missions. Each mission consists of a predefined sequence of tasks, connected by logical rules. Activation and completion Fig. 3: Layout of the software architecture.

6 6 Donato Di Paola, Annalisa Milella, and Grazia Cicirelli of missions and tasks are triggered by input and output events, respectively. In order to execute each task, we assume that a set of behaviours, i.e. simple reactive actions, is properly activated on board each robot. The layout of the software architecture is shown in Figure 3. It consists of the following main parts: the high-level control, communication, and localization and identification modules, running on the workstation, and the execution module running on each robot. All components are executed on a discrete-time basis: state updates, event detection, and commands are all processed at the beginning of each sample time. The Controller implements high-level control functionalities, monitoring mission execution and performing task assignment. In this module, one or more controller can be run. Each controller, called leader, is in charge of controlling a part of the network, in terms of missions and tasks. More specifically, each leader controls the execution of the missions in progress (e.g., guaranteeing the satisfaction of precedence constraints), sends the configuration information about the tasks that must be started on each robot, and receives information about the completed tasks. Each leader performs its work using a discrete-event model of the domain, a task execution controller, and a conflict resolution strategy, which will be described in the following section. Obviously, if only one leader exists, the control of the network can be viewed as a centralized system. The Executor performs the control at the lower level. This component is implemented on each robot through a set of tasks and a set of behaviours needed to accomplish a given goal. For each task, multiple behaviours can be executed at the same time. Each behaviour computes an output and when multiple behaviours are active at the same time, a predefined behaviour arbitration algorithm (e.g., subsumption [11] or cooperative methods [12]) can be used to obtain the final control signal. Currently, in our system, a subsumption mechanism is implemented. At the end of a task, the completion flag and the results are sent to the upper level. Communication between the Executor and the Controller is guaranteed by the Communication module. This module provides all high-level control commands from the leaders to the other robots in the network. In particular, in this module, the proper communication libraries are loaded, according to the specified robot. Moreover, the communication module is connected to the vision based localization and identification module that provides, for each robot, position and identity information, used to accomplish an assigned task and for behaviour control. It is worth to note that, although the main objective of this work is that of providing an experimental platform, the proposed system may also be used as a simulation tool by substituting the Executor with an additional Simulation module. The latter, which uses the same interface with the Communication module as the Executor, simulates the behaviour of each robot in a virtual environment, providing robot positions and simulating task execution. In the rest of this section, further details concerning the hybrid control of the network, as well as the localization and identification module, are provided.

7 An Experimental Testbed for Robotic Network Applications Robot Network Control As mentioned above, the control of the network is distributed among the components of the architecture. The overall management of the robotic network is based on a hybrid control framework: the global network activities are modeled and controlled as a Discrete Event System (DES) and the low-level behaviours, for each robot, are considered as continuous-time control algorithms trigged by the DES supervisor. Moreover, the global model of the network is distributed among a set of leaders. Each leader can control all activities or a sub-set of them in the network. The activities domain of the network is modeled as follows: each robot must execute a set of missions; each mission is a set of atomic tasks, which may be subject to priority constraints (i.e., the end of one task may be a necessary prerequisite for the start of some other ones). To execute each task, the robot must perform a predetermined sequence of behaviours (e.g. GoTo, AvoidObstacle, WallFollowing, Wandering, etc.). Each behaviour runs until an event (either triggered by sensor data or by the supervisory controller) occurs. Two or more behaviours can be active simultaneously. In such a case, the behaviour arbitration algorithm, on board the robot, computes the appropriate command to be sent to robot actuators. Missions may be triggered at unknown times, while the number and type of tasks composing a mission is known a priori. Since different missions can run simultaneously, different tasks may require the same subset of robots. In these cases, conflicts between the robots have to be handled using an efficient task allocation policy in order to avoid deadlock situations. The overall control scheme, proposed in this work, is based on the Matrix-based Discrete Event modeling and control Framework (MDEF) [13], a tool for modelling and analyzing complex interconnected DES with shared resources, for routing decisions, and managing dynamic resources. More precisely, in this work a partial decentralization of the MDEF is implemented. The set of leaders are considered as a group of centralized MDEFs working on separate parts of the network [14]. All the MDEF builds over a set of key matrices and vectors. Although this presentation is mainly intended for self-containment purposes, it is obviously not possible to provide all the details of the formalism in the limited space available here. Reader therefore is referred to [14] for further details. Suppose that the RN is composed of V = {v 1,...,v n } robots, which have to accomplish M = {m 1,...,m l } missions. Each mission is, in turn, viewable as a sequence of primitive tasks (e.g., reach the target, take a picture of the target, measure the temperature, collect the target, etc.), which requires some low-level behaviors and may be subject to precedence constraints (e.g., the target can be collected after it has been found). Thus, T = {t 1,...,t m } denotes the set of all possible tasks for the RN. The execution of tasks is governed by a set of rules. More specifically, each rule specifies all the preconditions for tasks execution, and the resulting consequences (postconditions). All rules for all missions in M are defined by the set X = {x 1,...,x q }. Thus a mission m j is associated to a specific set of rules X m j X. The set of all possible input events (a sensory input, a user command, etc.) is indicated as U = {u 1,...,u p }. One or more inputs can be considered as

8 8 Donato Di Paola, Annalisa Milella, and Grazia Cicirelli preconditions for a generic mission m j, thus these event are element of the set U m j U. Besides tasks and rules, generic outputs can be considered as postconditions. All possible outputs in the network are indicated by the set Y = {y 1,...,y o }. Briefly, the MDEF controls the execution of tasks by checking the status of the rules at each time sample. Each rule whose preconditions are all true in the current time sample is fired, i.e., all the actions described in the consequent part of the rule are triggered. The result of the logical preconditions evaluation provide the information needed to properly trigger tasks. Since conflicts in the assignment of tasks can occur, before starting the execution of task a multi-agent task allocation algorithm is performed, such as the Look-Ahead strategy proposed in [15]. After the task allocation step, postconditions are fired properly and robots start assigned tasks and eventually output events are produced Robot Identification and Localization Robot identification and localization is performed using a vision-based tracking system. Indeed, E-Puck robots are equipped with encoders, and therefore odometry could be adopted for robot location estimate. Nevertheless, we use an external camera, since it provides an absolute positioning system, thus avoiding error accumulation problems. In addition, based on visual information, the robot identification issue can be easily solved. We developed an algorithm that is able to simultaneously estimate the global positions of all the robots in the arena, determining, at the same time, which location belongs to which robot. We call this module Simultaneous Localization and Identification (SLI). The output of the SLI module is fed into the control system. It is assumed that each robot is equipped with a circular coloured hat (see Figure 2(b)). Different colours are used for the different robots. Each hat serves as (a) (b) Fig. 4: Results of the SLI module: (a) wandering behaviour; (b) wall-following behaviour.

9 An Experimental Testbed for Robotic Network Applications 9 an artificial landmark for robot detection and identification. Specifically, the SLI includes a semi-automatic learning procedure that allows us to learn and store a model for each landmark; then, based on this model, it performs robot localization and identification through a model matching technique. The learning phase consists of the following steps. First, various pictures of each robot in the arena are acquired by the overhead camera; then, in each picture a polygonal area containing the robot is selected manually, and shape and colour information are extracted by analyzing the pixels of the selected area. Shape information is represented by using the radius of the minimum enclosing circle for the selected polygonal area. Colour is defined, instead, by a three-dimensional vector containing the median of each color component in the HSV color space. The procedure is repeated for all the pictures, and median values for both the radius and the color vector are computed and stored. Once the model of each robot has been learned, it can be used for detecting and identifying all the robots in the arena. The detection phase is based on a Circular Hough Transform, which allows one to detect all the circular objects within a specified radius interval based on the results of the model learning phase. Then, the pixels internal to each detected circle are analyzed for robot identification, using colour information. Specifically, the median of hue, saturation and value of the pixels internal to each circle are computed and are stored in a 3D color vector, which is then compared with the available robot models. A circle is finally recognized as being one of the robots if the Euclidean distance between its associated color vector and the closest robot color model is less than an experimentally determined threshold. At this step, the position of each robot is expressed as pixel coordinates of the centre of the circle in the image reference frame. A camera calibration procedure performed once, after camera installation, allows us to transform the pixel position in a real-world position. In order to improve the performance of the algorithm in terms of speed and accuracy of both detection and identification phase, we implemented a Kalman filter-based robot tracking. As an example, Figure 4 shows the result of the SLI module for four robots in two different experiments. Specifically, in Figure 4(a) the robots are tracked while wandering in the arena; in Figure 4(b), each robot carries out a wall-following task. 3 Experimental Results In this section, we show the results of an experimental test performed using the setup described in the previous sections. In this experiment, the network evolves from a single-leader configuration to a multiple-leader configuration, in order for the robots to perform exploration tasks in different parts of the arena starting from a rendez vous position. In the various phases of the test, the leader robots can be distinguished from the other ones, as they are green-lighted. In Figure 5(a), the four robots form a unique network with one leader (i.e., the green-lighted robot with the red hat). Figure 5(b) shows the trajectories of the four robots while going to

10 10 Donato Di Paola, Annalisa Milella, and Grazia Cicirelli the rendez vous position. Successively, the network splits into two sub-networks of two robots each (Figure 5(c)). Both networks have their own leader (i.e., the greenlighted robot with the blue hat and the green-lighted robot with the red hat). The two teams reach opposite sides of the arena to explore different areas. Figure 5(d) shows the tracked trajectories of the robots after the splitting of the network. The graph in Figure 6 shows the time trace of the experiment. This graph can be easily obtained by the saved data of the logging system. In particular, in this figure, we show: the network configuration, i.e. the single leader network (Network AB), and the two sub-networks (Network A and Network B); the missions in progress; the robots assigned to each mission and their network; the activation of tasks. For all these information a line representing high (activation) or low (deactivation) state is depicted. In Table 1, the correspondences among missions, robot networks, robots and tasks are reported for better understanding the graph in Figure 6. It can be noticed that Mission 1, which involves all robots (i.e., Network AB), starts at sampling instant 7. This mission is accomplished at time 33, when each robot in the network terminates Task 1, that is, the GoToGoal task, in order to reach the rendez vous (a) (b) (c) (d) Fig. 5: (a)-(b) Rendez vous of the networked robots with a unique leader; (c)-(d) splitting of the network into two sub-networks with two different leaders to explore opposite sides of the arena

11 An Experimental Testbed for Robotic Network Applications 11 Table 1: Correspondences among missions, robot networks, robots, and tasks Mission ID Network Name Robot ID Task ID 1 AB 1,2,3, B 2,4 1,3 3 A 1,3 1,2 point at the centre of the arena. After Mission 1, the network splits into the two sub-networks A and B. As we note, network B starts Mission 2 before network A at the time instant 33. Obviously, the robots #2 and #4, which are members of network B, become busy when Mission 2 starts, performing, first, Task 1 and, then, at time 47, Task 3 (WallFollowing). At the instant 36, Mission 3 starts involving robots #1 and #3. Network A, first, performs Task 1 and, then, Task 2 (ExploreEnvironment). At completion of Mission 3, at time 68, the robots of network A become available and all the tasks they are involved in terminate. Finally, at time 74, Mission 2 is accomplished, robots #2 and #4 are released, and all tasks in the whole network are successfully terminated. Fig. 6: Time trace graph for the experiment of Figure 5.

12 12 Donato Di Paola, Annalisa Milella, and Grazia Cicirelli 4 Conclusions We described an experimental set-up for multi-robot applications. The small sized, relatively simple robots E-Puck are utilized. A USB camera connected to a high speed PC is adopted for robot monitoring and global positioning. Image processing provides the positions of the robots to the control algorithms. The latter are based on discrete event framework, for the high level control, and a task and behaviour-based distributed control framework at the lower level. We believe that this test bed is a useful experimental facility, which can be employed for testing multi-robot coordination and control algorithms in graduate and undergraduate courses as well as for research purposes. References 1. Burgard, W., Moors, M., Stachniss, C., and Schneider. F., Coordinated multi-robot exploration. In IEEE Transactions on Robotics, 21(3). 2. Fierro, R., Das, A.,, Spletzer, J., Esposito J., Kumar, V., Ostrowski, J.P., Pappas, G., Taylor C.J., Hur Y., Alur, R., Lee, I., Grudic G., Ben Southall, B., A Framework and Architecture for Multi-Robot Coordination, In The International Journal of Robotics Research, 21(10-11), pp Kumar, V., Rus, D., and Singh, S., Robot and sensor networks for first responders, In IEEE Pervasive Computing, vol. 3, no. 4, pp , Oct. 4. Vincent, R., Fox, D., Ko, J., Konolige, K., Limketkai, B., Morisset, B., Ortiz, C., Schulz, D., and Stewart, B., Distributed multirobot exploration, mapping, and task allocation. In Annals of Mathematics and Artificial Intelligence, Springer Netherlands. 5. Pugh, J. and Martinoli, A., Multi-robot learning with particle swarm optimization. In Proceedings of the Fifth International Joint Conference on Autonomous Agents and Multiagent Systems. 6. Lerman, K., Chris Jones, C., Galstyan, A., Matarc, M.J Analysis of Dynamic Task Allocation in Multi-Robot Systems, International Journal of Robotics Research, 25(3), pp Viguria, A., Maza, I., and Ollero, A., SET: An algorithm for distributed multirobot task allocation with dynamic negotiation based on task subsets. In Proc. of 2007 IEEE International Conference on Robotics and Automation, Roma, Italy. 8. Werner, F., Rckert, U., Tanoto, A, Welzel, J The Teleworkbench A Platform for Performing and Comparing Experiments in Robot Navigation, IEEE International Conference on Robotics and Automation (ICRA), Anchorage, AK, USA 9. Mondada, F., Franzi, E. and Guignard, A., The Development of Khepera. In Experiments with the Mini-Robot Khepera, pp Mondada, F., Bonani, M., Raemy, X., Pugh, J., Cianci, C., Klaptocz, A., Magnenat, S., Zufferey, J.-C., Floreano, D. and Martinoli, A., The E-Puck, a Robot Designed for Education in Engineering. In Proceedings of the 9th Conference on Autonomous Robot Systems and Competitions, 1(1) pp Brooks R.A., Intelligence without Representation. In Artificial Intelligence, Vol.47, pp Payton D.W., Keirsey D., Kimble D.M., Krozel J. and Rosenblatt J.K., Do whatever works: A robust approach to fault-tolerant autonomous control, In Applied Intelligence, 2 (3), pp

13 An Experimental Testbed for Robotic Network Applications Tacconi, D., Lewis, F., A new matrix model for discrete event systems: application to simulation. In IEEE Control System Magazine, Volume 17, Issue 5, pp Di Paola, D., Gasparri, A., Naso, D., Ulivi, G., and Lewis, F. L., Decentralized Task Sequencing and Multiple Mission Control for Heterogeneous Robotic Networks, In Proc. of IEEE International Conference on Robotics and Automation. 15. Di Paola, D., Naso, D., and Turchiano, B., A Heuristic Approach to Task Assignment and Control for Robotic Networks, In Proc. of the IEEE International Symposium on Industrial Electronics (ISIE).

MULTI-LAYERED HYBRID ARCHITECTURE TO SOLVE COMPLEX TASKS OF AN AUTONOMOUS MOBILE ROBOT

MULTI-LAYERED HYBRID ARCHITECTURE TO SOLVE COMPLEX TASKS OF AN AUTONOMOUS MOBILE ROBOT MULTI-LAYERED HYBRID ARCHITECTURE TO SOLVE COMPLEX TASKS OF AN AUTONOMOUS MOBILE ROBOT F. TIECHE, C. FACCHINETTI and H. HUGLI Institute of Microtechnology, University of Neuchâtel, Rue de Tivoli 28, CH-2003

More information

Lab 8: Introduction to the e-puck Robot

Lab 8: Introduction to the e-puck Robot Lab 8: Introduction to the e-puck Robot This laboratory requires the following equipment: C development tools (gcc, make, etc.) C30 programming tools for the e-puck robot The development tree which is

More information

Adaptive Action Selection without Explicit Communication for Multi-robot Box-pushing

Adaptive Action Selection without Explicit Communication for Multi-robot Box-pushing Adaptive Action Selection without Explicit Communication for Multi-robot Box-pushing Seiji Yamada Jun ya Saito CISS, IGSSE, Tokyo Institute of Technology 4259 Nagatsuta, Midori, Yokohama 226-8502, JAPAN

More information

Lab 7: Introduction to Webots and Sensor Modeling

Lab 7: Introduction to Webots and Sensor Modeling Lab 7: Introduction to Webots and Sensor Modeling This laboratory requires the following software: Webots simulator C development tools (gcc, make, etc.) The laboratory duration is approximately two hours.

More information

S.P.Q.R. Legged Team Report from RoboCup 2003

S.P.Q.R. Legged Team Report from RoboCup 2003 S.P.Q.R. Legged Team Report from RoboCup 2003 L. Iocchi and D. Nardi Dipartimento di Informatica e Sistemistica Universitá di Roma La Sapienza Via Salaria 113-00198 Roma, Italy {iocchi,nardi}@dis.uniroma1.it,

More information

Behaviour-Based Control. IAR Lecture 5 Barbara Webb

Behaviour-Based Control. IAR Lecture 5 Barbara Webb Behaviour-Based Control IAR Lecture 5 Barbara Webb Traditional sense-plan-act approach suggests a vertical (serial) task decomposition Sensors Actuators perception modelling planning task execution motor

More information

Robot Task-Level Programming Language and Simulation

Robot Task-Level Programming Language and Simulation Robot Task-Level Programming Language and Simulation M. Samaka Abstract This paper presents the development of a software application for Off-line robot task programming and simulation. Such application

More information

CNR-ISSIA. ISSIA: Summary Table. Istituto di Studi sui Sistemi Intelligenti per l Automazione, CNR Via G. Amendola 122/D-O Bari, Italy

CNR-ISSIA. ISSIA: Summary Table. Istituto di Studi sui Sistemi Intelligenti per l Automazione, CNR Via G. Amendola 122/D-O Bari, Italy CNR-ISSIA ISSIA: Summary Table Institute Istituto di Studi sui Sistemi Intelligenti per l Automazione, CNR Via G. Amendola 122/D-O - 70126 Bari, Italy Year of foundation Refererence person Website Dr.

More information

Traffic Control for a Swarm of Robots: Avoiding Target Congestion

Traffic Control for a Swarm of Robots: Avoiding Target Congestion Traffic Control for a Swarm of Robots: Avoiding Target Congestion Leandro Soriano Marcolino and Luiz Chaimowicz Abstract One of the main problems in the navigation of robotic swarms is when several robots

More information

Multi-Robot Coordination. Chapter 11

Multi-Robot Coordination. Chapter 11 Multi-Robot Coordination Chapter 11 Objectives To understand some of the problems being studied with multiple robots To understand the challenges involved with coordinating robots To investigate a simple

More information

A Robotic Simulator Tool for Mobile Robots

A Robotic Simulator Tool for Mobile Robots 2016 Published in 4th International Symposium on Innovative Technologies in Engineering and Science 3-5 November 2016 (ISITES2016 Alanya/Antalya - Turkey) A Robotic Simulator Tool for Mobile Robots 1 Mehmet

More information

Creating a 3D environment map from 2D camera images in robotics

Creating a 3D environment map from 2D camera images in robotics Creating a 3D environment map from 2D camera images in robotics J.P. Niemantsverdriet jelle@niemantsverdriet.nl 4th June 2003 Timorstraat 6A 9715 LE Groningen student number: 0919462 internal advisor:

More information

Semi-Autonomous Parking for Enhanced Safety and Efficiency

Semi-Autonomous Parking for Enhanced Safety and Efficiency Technical Report 105 Semi-Autonomous Parking for Enhanced Safety and Efficiency Sriram Vishwanath WNCG June 2017 Data-Supported Transportation Operations & Planning Center (D-STOP) A Tier 1 USDOT University

More information

NCCT IEEE PROJECTS ADVANCED ROBOTICS SOLUTIONS. Latest Projects, in various Domains. Promise for the Best Projects

NCCT IEEE PROJECTS ADVANCED ROBOTICS SOLUTIONS. Latest Projects, in various Domains. Promise for the Best Projects NCCT Promise for the Best Projects IEEE PROJECTS in various Domains Latest Projects, 2009-2010 ADVANCED ROBOTICS SOLUTIONS EMBEDDED SYSTEM PROJECTS Microcontrollers VLSI DSP Matlab Robotics ADVANCED ROBOTICS

More information

Motion Control of a Three Active Wheeled Mobile Robot and Collision-Free Human Following Navigation in Outdoor Environment

Motion Control of a Three Active Wheeled Mobile Robot and Collision-Free Human Following Navigation in Outdoor Environment Proceedings of the International MultiConference of Engineers and Computer Scientists 2016 Vol I,, March 16-18, 2016, Hong Kong Motion Control of a Three Active Wheeled Mobile Robot and Collision-Free

More information

Traffic Control for a Swarm of Robots: Avoiding Group Conflicts

Traffic Control for a Swarm of Robots: Avoiding Group Conflicts Traffic Control for a Swarm of Robots: Avoiding Group Conflicts Leandro Soriano Marcolino and Luiz Chaimowicz Abstract A very common problem in the navigation of robotic swarms is when groups of robots

More information

DEVELOPMENT OF A ROBOID COMPONENT FOR PLAYER/STAGE ROBOT SIMULATOR

DEVELOPMENT OF A ROBOID COMPONENT FOR PLAYER/STAGE ROBOT SIMULATOR Proceedings of IC-NIDC2009 DEVELOPMENT OF A ROBOID COMPONENT FOR PLAYER/STAGE ROBOT SIMULATOR Jun Won Lim 1, Sanghoon Lee 2,Il Hong Suh 1, and Kyung Jin Kim 3 1 Dept. Of Electronics and Computer Engineering,

More information

Swarm Intelligence W7: Application of Machine- Learning Techniques to Automatic Control Design and Optimization

Swarm Intelligence W7: Application of Machine- Learning Techniques to Automatic Control Design and Optimization Swarm Intelligence W7: Application of Machine- Learning Techniques to Automatic Control Design and Optimization Learning to avoid obstacles Outline Problem encoding using GA and ANN Floreano and Mondada

More information

NAVIGATION OF MOBILE ROBOT USING THE PSO PARTICLE SWARM OPTIMIZATION

NAVIGATION OF MOBILE ROBOT USING THE PSO PARTICLE SWARM OPTIMIZATION Journal of Academic and Applied Studies (JAAS) Vol. 2(1) Jan 2012, pp. 32-38 Available online @ www.academians.org ISSN1925-931X NAVIGATION OF MOBILE ROBOT USING THE PSO PARTICLE SWARM OPTIMIZATION Sedigheh

More information

AN AUTONOMOUS SIMULATION BASED SYSTEM FOR ROBOTIC SERVICES IN PARTIALLY KNOWN ENVIRONMENTS

AN AUTONOMOUS SIMULATION BASED SYSTEM FOR ROBOTIC SERVICES IN PARTIALLY KNOWN ENVIRONMENTS AN AUTONOMOUS SIMULATION BASED SYSTEM FOR ROBOTIC SERVICES IN PARTIALLY KNOWN ENVIRONMENTS Eva Cipi, PhD in Computer Engineering University of Vlora, Albania Abstract This paper is focused on presenting

More information

RescueRobot: Simulating Complex Robots Behaviors in Emergency Situations

RescueRobot: Simulating Complex Robots Behaviors in Emergency Situations RescueRobot: Simulating Complex Robots Behaviors in Emergency Situations Giuseppe Palestra, Andrea Pazienza, Stefano Ferilli, Berardina De Carolis, and Floriana Esposito Dipartimento di Informatica Università

More information

Correcting Odometry Errors for Mobile Robots Using Image Processing

Correcting Odometry Errors for Mobile Robots Using Image Processing Correcting Odometry Errors for Mobile Robots Using Image Processing Adrian Korodi, Toma L. Dragomir Abstract - The mobile robots that are moving in partially known environments have a low availability,

More information

Multi-Robot Cooperative System For Object Detection

Multi-Robot Cooperative System For Object Detection Multi-Robot Cooperative System For Object Detection Duaa Abdel-Fattah Mehiar AL-Khawarizmi international collage Duaa.mehiar@kawarizmi.com Abstract- The present study proposes a multi-agent system based

More information

* Intelli Robotic Wheel Chair for Specialty Operations & Physically Challenged

* Intelli Robotic Wheel Chair for Specialty Operations & Physically Challenged ADVANCED ROBOTICS SOLUTIONS * Intelli Mobile Robot for Multi Specialty Operations * Advanced Robotic Pick and Place Arm and Hand System * Automatic Color Sensing Robot using PC * AI Based Image Capturing

More information

Mobile Robots Exploration and Mapping in 2D

Mobile Robots Exploration and Mapping in 2D ASEE 2014 Zone I Conference, April 3-5, 2014, University of Bridgeport, Bridgpeort, CT, USA. Mobile Robots Exploration and Mapping in 2D Sithisone Kalaya Robotics, Intelligent Sensing & Control (RISC)

More information

Path Following and Obstacle Avoidance Fuzzy Controller for Mobile Indoor Robots

Path Following and Obstacle Avoidance Fuzzy Controller for Mobile Indoor Robots Path Following and Obstacle Avoidance Fuzzy Controller for Mobile Indoor Robots Mousa AL-Akhras, Maha Saadeh, Emad AL Mashakbeh Computer Information Systems Department King Abdullah II School for Information

More information

Proseminar Roboter und Aktivmedien. Outline of today s lecture. Acknowledgments. Educational robots achievements and challenging

Proseminar Roboter und Aktivmedien. Outline of today s lecture. Acknowledgments. Educational robots achievements and challenging Proseminar Roboter und Aktivmedien Educational robots achievements and challenging Lecturer Lecturer Houxiang Houxiang Zhang Zhang TAMS, TAMS, Department Department of of Informatics Informatics University

More information

Key-Words: - Fuzzy Behaviour Controls, Multiple Target Tracking, Obstacle Avoidance, Ultrasonic Range Finders

Key-Words: - Fuzzy Behaviour Controls, Multiple Target Tracking, Obstacle Avoidance, Ultrasonic Range Finders Fuzzy Behaviour Based Navigation of a Mobile Robot for Tracking Multiple Targets in an Unstructured Environment NASIR RAHMAN, ALI RAZA JAFRI, M. USMAN KEERIO School of Mechatronics Engineering Beijing

More information

A Design for the Integration of Sensors to a Mobile Robot. Mentor: Dr. Geb Thomas. Mentee: Chelsey N. Daniels

A Design for the Integration of Sensors to a Mobile Robot. Mentor: Dr. Geb Thomas. Mentee: Chelsey N. Daniels A Design for the Integration of Sensors to a Mobile Robot Mentor: Dr. Geb Thomas Mentee: Chelsey N. Daniels 7/19/2007 Abstract The robot localization problem is the challenge of accurately tracking robots

More information

CYCLIC GENETIC ALGORITHMS FOR EVOLVING MULTI-LOOP CONTROL PROGRAMS

CYCLIC GENETIC ALGORITHMS FOR EVOLVING MULTI-LOOP CONTROL PROGRAMS CYCLIC GENETIC ALGORITHMS FOR EVOLVING MULTI-LOOP CONTROL PROGRAMS GARY B. PARKER, CONNECTICUT COLLEGE, USA, parker@conncoll.edu IVO I. PARASHKEVOV, CONNECTICUT COLLEGE, USA, iipar@conncoll.edu H. JOSEPH

More information

Multi-Agent Planning

Multi-Agent Planning 25 PRICAI 2000 Workshop on Teams with Adjustable Autonomy PRICAI 2000 Workshop on Teams with Adjustable Autonomy Position Paper Designing an architecture for adjustably autonomous robot teams David Kortenkamp

More information

Learning Reactive Neurocontrollers using Simulated Annealing for Mobile Robots

Learning Reactive Neurocontrollers using Simulated Annealing for Mobile Robots Learning Reactive Neurocontrollers using Simulated Annealing for Mobile Robots Philippe Lucidarme, Alain Liégeois LIRMM, University Montpellier II, France, lucidarm@lirmm.fr Abstract This paper presents

More information

Face Detector using Network-based Services for a Remote Robot Application

Face Detector using Network-based Services for a Remote Robot Application Face Detector using Network-based Services for a Remote Robot Application Yong-Ho Seo Department of Intelligent Robot Engineering, Mokwon University Mokwon Gil 21, Seo-gu, Daejeon, Republic of Korea yhseo@mokwon.ac.kr

More information

Using Reactive Deliberation for Real-Time Control of Soccer-Playing Robots

Using Reactive Deliberation for Real-Time Control of Soccer-Playing Robots Using Reactive Deliberation for Real-Time Control of Soccer-Playing Robots Yu Zhang and Alan K. Mackworth Department of Computer Science, University of British Columbia, Vancouver B.C. V6T 1Z4, Canada,

More information

Randomized Motion Planning for Groups of Nonholonomic Robots

Randomized Motion Planning for Groups of Nonholonomic Robots Randomized Motion Planning for Groups of Nonholonomic Robots Christopher M Clark chrisc@sun-valleystanfordedu Stephen Rock rock@sun-valleystanfordedu Department of Aeronautics & Astronautics Stanford University

More information

A User Friendly Software Framework for Mobile Robot Control

A User Friendly Software Framework for Mobile Robot Control A User Friendly Software Framework for Mobile Robot Control Jesse Riddle, Ryan Hughes, Nathaniel Biefeld, and Suranga Hettiarachchi Computer Science Department, Indiana University Southeast New Albany,

More information

MULTI ROBOT COMMUNICATION AND TARGET TRACKING SYSTEM AND IMPLEMENTATION OF ROBOT USING ARDUINO

MULTI ROBOT COMMUNICATION AND TARGET TRACKING SYSTEM AND IMPLEMENTATION OF ROBOT USING ARDUINO MULTI ROBOT COMMUNICATION AND TARGET TRACKING SYSTEM AND IMPLEMENTATION OF ROBOT USING ARDUINO K. Sindhuja 1, CH. Lavanya 2 1Student, Department of ECE, GIST College, Andhra Pradesh, INDIA 2Assistant Professor,

More information

Multi robot Team Formation for Distributed Area Coverage. Raj Dasgupta Computer Science Department University of Nebraska, Omaha

Multi robot Team Formation for Distributed Area Coverage. Raj Dasgupta Computer Science Department University of Nebraska, Omaha Multi robot Team Formation for Distributed Area Coverage Raj Dasgupta Computer Science Department University of Nebraska, Omaha C MANTIC Lab Collaborative Multi AgeNt/Multi robot Technologies for Intelligent

More information

Dipartimento di Elettronica Informazione e Bioingegneria Robotics

Dipartimento di Elettronica Informazione e Bioingegneria Robotics Dipartimento di Elettronica Informazione e Bioingegneria Robotics Behavioral robotics @ 2014 Behaviorism behave is what organisms do Behaviorism is built on this assumption, and its goal is to promote

More information

Kilobot: A Robotic Module for Demonstrating Behaviors in a Large Scale (\(2^{10}\) Units) Collective

Kilobot: A Robotic Module for Demonstrating Behaviors in a Large Scale (\(2^{10}\) Units) Collective Kilobot: A Robotic Module for Demonstrating Behaviors in a Large Scale (\(2^{10}\) Units) Collective The Harvard community has made this article openly available. Please share how this access benefits

More information

Obstacle avoidance based on fuzzy logic method for mobile robots in Cluttered Environment

Obstacle avoidance based on fuzzy logic method for mobile robots in Cluttered Environment Obstacle avoidance based on fuzzy logic method for mobile robots in Cluttered Environment Fatma Boufera 1, Fatima Debbat 2 1,2 Mustapha Stambouli University, Math and Computer Science Department Faculty

More information

SPQR RoboCup 2016 Standard Platform League Qualification Report

SPQR RoboCup 2016 Standard Platform League Qualification Report SPQR RoboCup 2016 Standard Platform League Qualification Report V. Suriani, F. Riccio, L. Iocchi, D. Nardi Dipartimento di Ingegneria Informatica, Automatica e Gestionale Antonio Ruberti Sapienza Università

More information

Implicit Fitness Functions for Evolving a Drawing Robot

Implicit Fitness Functions for Evolving a Drawing Robot Implicit Fitness Functions for Evolving a Drawing Robot Jon Bird, Phil Husbands, Martin Perris, Bill Bigge and Paul Brown Centre for Computational Neuroscience and Robotics University of Sussex, Brighton,

More information

Multi-robot Formation Control Based on Leader-follower Method

Multi-robot Formation Control Based on Leader-follower Method Journal of Computers Vol. 29 No. 2, 2018, pp. 233-240 doi:10.3966/199115992018042902022 Multi-robot Formation Control Based on Leader-follower Method Xibao Wu 1*, Wenbai Chen 1, Fangfang Ji 1, Jixing Ye

More information

A Mobile Robot Behavior Based Navigation Architecture using a Linear Graph of Passages as Landmarks for Path Definition

A Mobile Robot Behavior Based Navigation Architecture using a Linear Graph of Passages as Landmarks for Path Definition A Mobile Robot Behavior Based Navigation Architecture using a Linear Graph of Passages as Landmarks for Path Definition LUBNEN NAME MOUSSI and MARCONI KOLM MADRID DSCE FEEC UNICAMP Av Albert Einstein,

More information

Artificial Neural Network based Mobile Robot Navigation

Artificial Neural Network based Mobile Robot Navigation Artificial Neural Network based Mobile Robot Navigation István Engedy Budapest University of Technology and Economics, Department of Measurement and Information Systems, Magyar tudósok körútja 2. H-1117,

More information

AGENT PLATFORM FOR ROBOT CONTROL IN REAL-TIME DYNAMIC ENVIRONMENTS. Nuno Sousa Eugénio Oliveira

AGENT PLATFORM FOR ROBOT CONTROL IN REAL-TIME DYNAMIC ENVIRONMENTS. Nuno Sousa Eugénio Oliveira AGENT PLATFORM FOR ROBOT CONTROL IN REAL-TIME DYNAMIC ENVIRONMENTS Nuno Sousa Eugénio Oliveira Faculdade de Egenharia da Universidade do Porto, Portugal Abstract: This paper describes a platform that enables

More information

A Robust Neural Robot Navigation Using a Combination of Deliberative and Reactive Control Architectures

A Robust Neural Robot Navigation Using a Combination of Deliberative and Reactive Control Architectures A Robust Neural Robot Navigation Using a Combination of Deliberative and Reactive Control Architectures D.M. Rojas Castro, A. Revel and M. Ménard * Laboratory of Informatics, Image and Interaction (L3I)

More information

Limits of a Distributed Intelligent Networked Device in the Intelligence Space. 1 Brief History of the Intelligent Space

Limits of a Distributed Intelligent Networked Device in the Intelligence Space. 1 Brief History of the Intelligent Space Limits of a Distributed Intelligent Networked Device in the Intelligence Space Gyula Max, Peter Szemes Budapest University of Technology and Economics, H-1521, Budapest, Po. Box. 91. HUNGARY, Tel: +36

More information

Learning and Using Models of Kicking Motions for Legged Robots

Learning and Using Models of Kicking Motions for Legged Robots Learning and Using Models of Kicking Motions for Legged Robots Sonia Chernova and Manuela Veloso Computer Science Department Carnegie Mellon University Pittsburgh, PA 15213 {soniac, mmv}@cs.cmu.edu Abstract

More information

CS594, Section 30682:

CS594, Section 30682: CS594, Section 30682: Distributed Intelligence in Autonomous Robotics Spring 2003 Tuesday/Thursday 11:10 12:25 http://www.cs.utk.edu/~parker/courses/cs594-spring03 Instructor: Dr. Lynne E. Parker ½ TA:

More information

Gregory Bock, Brittany Dhall, Ryan Hendrickson, & Jared Lamkin Project Advisors: Dr. Jing Wang & Dr. In Soo Ahn Department of Electrical and Computer

Gregory Bock, Brittany Dhall, Ryan Hendrickson, & Jared Lamkin Project Advisors: Dr. Jing Wang & Dr. In Soo Ahn Department of Electrical and Computer Gregory Bock, Brittany Dhall, Ryan Hendrickson, & Jared Lamkin Project Advisors: Dr. Jing Wang & Dr. In Soo Ahn Department of Electrical and Computer Engineering March 1 st, 2016 Outline 2 I. Introduction

More information

Moving Obstacle Avoidance for Mobile Robot Moving on Designated Path

Moving Obstacle Avoidance for Mobile Robot Moving on Designated Path Moving Obstacle Avoidance for Mobile Robot Moving on Designated Path Taichi Yamada 1, Yeow Li Sa 1 and Akihisa Ohya 1 1 Graduate School of Systems and Information Engineering, University of Tsukuba, 1-1-1,

More information

The Khepera Robot and the krobot Class: A Platform for Introducing Robotics in the Undergraduate Curriculum i

The Khepera Robot and the krobot Class: A Platform for Introducing Robotics in the Undergraduate Curriculum i The Khepera Robot and the krobot Class: A Platform for Introducing Robotics in the Undergraduate Curriculum i Robert M. Harlan David B. Levine Shelley McClarigan Computer Science Department St. Bonaventure

More information

UNIVERSIDAD CARLOS III DE MADRID ESCUELA POLITÉCNICA SUPERIOR

UNIVERSIDAD CARLOS III DE MADRID ESCUELA POLITÉCNICA SUPERIOR UNIVERSIDAD CARLOS III DE MADRID ESCUELA POLITÉCNICA SUPERIOR TRABAJO DE FIN DE GRADO GRADO EN INGENIERÍA DE SISTEMAS DE COMUNICACIONES CONTROL CENTRALIZADO DE FLOTAS DE ROBOTS CENTRALIZED CONTROL FOR

More information

Effect of Sensor and Actuator Quality on Robot Swarm Algorithm Performance

Effect of Sensor and Actuator Quality on Robot Swarm Algorithm Performance 2011 IEEE/RSJ International Conference on Intelligent Robots and Systems September 25-30, 2011. San Francisco, CA, USA Effect of Sensor and Actuator Quality on Robot Swarm Algorithm Performance Nicholas

More information

Intelligent Tactical Robotics

Intelligent Tactical Robotics Intelligent Tactical Robotics Samana Jafri 1,Abbas Zair Naqvi 2, Manish Singh 3, Akhilesh Thorat 4 1 Dept. Of Electronics and telecommunication, M.H. Saboo Siddik College Of Engineering, Mumbai University

More information

Distributed Vision System: A Perceptual Information Infrastructure for Robot Navigation

Distributed Vision System: A Perceptual Information Infrastructure for Robot Navigation Distributed Vision System: A Perceptual Information Infrastructure for Robot Navigation Hiroshi Ishiguro Department of Information Science, Kyoto University Sakyo-ku, Kyoto 606-01, Japan E-mail: ishiguro@kuis.kyoto-u.ac.jp

More information

2013 RESEARCH EXPERIENCE FOR TEACHERS - ROBOTICS

2013 RESEARCH EXPERIENCE FOR TEACHERS - ROBOTICS 2013 RESEARCH EXPERIENCE FOR TEACHERS - ROBOTICS ELIZABETH FREEMAN JESSE BELL RET (Research Experiences for Teachers) Site on Networks, Electrical Engineering Department, and Institute of Applied Sciences,

More information

Displacement Measurement of Burr Arch-Truss Under Dynamic Loading Based on Image Processing Technology

Displacement Measurement of Burr Arch-Truss Under Dynamic Loading Based on Image Processing Technology 6 th International Conference on Advances in Experimental Structural Engineering 11 th International Workshop on Advanced Smart Materials and Smart Structures Technology August 1-2, 2015, University of

More information

1 Lab + Hwk 4: Introduction to the e-puck Robot

1 Lab + Hwk 4: Introduction to the e-puck Robot 1 Lab + Hwk 4: Introduction to the e-puck Robot This laboratory requires the following: (The development tools are already installed on the DISAL virtual machine (Ubuntu Linux) in GR B0 01): C development

More information

Navigation of Transport Mobile Robot in Bionic Assembly System

Navigation of Transport Mobile Robot in Bionic Assembly System Navigation of Transport Mobile obot in Bionic ssembly System leksandar Lazinica Intelligent Manufacturing Systems IFT Karlsplatz 13/311, -1040 Vienna Tel : +43-1-58801-311141 Fax :+43-1-58801-31199 e-mail

More information

Available online at ScienceDirect. Procedia Computer Science 76 (2015 )

Available online at   ScienceDirect. Procedia Computer Science 76 (2015 ) Available online at www.sciencedirect.com ScienceDirect Procedia Computer Science 76 (2015 ) 474 479 2015 IEEE International Symposium on Robotics and Intelligent Sensors (IRIS 2015) Sensor Based Mobile

More information

Evolving High-Dimensional, Adaptive Camera-Based Speed Sensors

Evolving High-Dimensional, Adaptive Camera-Based Speed Sensors In: M.H. Hamza (ed.), Proceedings of the 21st IASTED Conference on Applied Informatics, pp. 1278-128. Held February, 1-1, 2, Insbruck, Austria Evolving High-Dimensional, Adaptive Camera-Based Speed Sensors

More information

An Agent-based Heterogeneous UAV Simulator Design

An Agent-based Heterogeneous UAV Simulator Design An Agent-based Heterogeneous UAV Simulator Design MARTIN LUNDELL 1, JINGPENG TANG 1, THADDEUS HOGAN 1, KENDALL NYGARD 2 1 Math, Science and Technology University of Minnesota Crookston Crookston, MN56716

More information

Simulation of a mobile robot navigation system

Simulation of a mobile robot navigation system Edith Cowan University Research Online ECU Publications 2011 2011 Simulation of a mobile robot navigation system Ahmed Khusheef Edith Cowan University Ganesh Kothapalli Edith Cowan University Majid Tolouei

More information

Embedded Robust Control of Self-balancing Two-wheeled Robot

Embedded Robust Control of Self-balancing Two-wheeled Robot Embedded Robust Control of Self-balancing Two-wheeled Robot L. Mollov, P. Petkov Key Words: Robust control; embedded systems; two-wheeled robots; -synthesis; MATLAB. Abstract. This paper presents the design

More information

Path Planning for Mobile Robots Based on Hybrid Architecture Platform

Path Planning for Mobile Robots Based on Hybrid Architecture Platform Path Planning for Mobile Robots Based on Hybrid Architecture Platform Ting Zhou, Xiaoping Fan & Shengyue Yang Laboratory of Networked Systems, Central South University, Changsha 410075, China Zhihua Qu

More information

Multi-Platform Soccer Robot Development System

Multi-Platform Soccer Robot Development System Multi-Platform Soccer Robot Development System Hui Wang, Han Wang, Chunmiao Wang, William Y. C. Soh Division of Control & Instrumentation, School of EEE Nanyang Technological University Nanyang Avenue,

More information

Artificial Beacons with RGB-D Environment Mapping for Indoor Mobile Robot Localization

Artificial Beacons with RGB-D Environment Mapping for Indoor Mobile Robot Localization Sensors and Materials, Vol. 28, No. 6 (2016) 695 705 MYU Tokyo 695 S & M 1227 Artificial Beacons with RGB-D Environment Mapping for Indoor Mobile Robot Localization Chun-Chi Lai and Kuo-Lan Su * Department

More information

Handling Failures In A Swarm

Handling Failures In A Swarm Handling Failures In A Swarm Gaurav Verma 1, Lakshay Garg 2, Mayank Mittal 3 Abstract Swarm robotics is an emerging field of robotics research which deals with the study of large groups of simple robots.

More information

SWARM-BOT: A Swarm of Autonomous Mobile Robots with Self-Assembling Capabilities

SWARM-BOT: A Swarm of Autonomous Mobile Robots with Self-Assembling Capabilities SWARM-BOT: A Swarm of Autonomous Mobile Robots with Self-Assembling Capabilities Francesco Mondada 1, Giovanni C. Pettinaro 2, Ivo Kwee 2, André Guignard 1, Luca Gambardella 2, Dario Floreano 1, Stefano

More information

Hierarchical Controller for Robotic Soccer

Hierarchical Controller for Robotic Soccer Hierarchical Controller for Robotic Soccer Byron Knoll Cognitive Systems 402 April 13, 2008 ABSTRACT RoboCup is an initiative aimed at advancing Artificial Intelligence (AI) and robotics research. This

More information

Subsumption Architecture in Swarm Robotics. Cuong Nguyen Viet 16/11/2015

Subsumption Architecture in Swarm Robotics. Cuong Nguyen Viet 16/11/2015 Subsumption Architecture in Swarm Robotics Cuong Nguyen Viet 16/11/2015 1 Table of content Motivation Subsumption Architecture Background Architecture decomposition Implementation Swarm robotics Swarm

More information

Learning serious knowledge while "playing"with robots

Learning serious knowledge while playingwith robots 6 th International Conference on Applied Informatics Eger, Hungary, January 27 31, 2004. Learning serious knowledge while "playing"with robots Zoltán Istenes Department of Software Technology and Methodology,

More information

Signals, Instruments, and Systems W7. Embedded Systems General Concepts and

Signals, Instruments, and Systems W7. Embedded Systems General Concepts and Signals, Instruments, and Systems W7 Introduction to Hardware in Embedded Systems General Concepts and the e-puck Example Outline General concepts: autonomy, perception, p action, computation, communication

More information

CMDragons 2009 Team Description

CMDragons 2009 Team Description CMDragons 2009 Team Description Stefan Zickler, Michael Licitra, Joydeep Biswas, and Manuela Veloso Carnegie Mellon University {szickler,mmv}@cs.cmu.edu {mlicitra,joydeep}@andrew.cmu.edu Abstract. In this

More information

A Probabilistic Method for Planning Collision-free Trajectories of Multiple Mobile Robots

A Probabilistic Method for Planning Collision-free Trajectories of Multiple Mobile Robots A Probabilistic Method for Planning Collision-free Trajectories of Multiple Mobile Robots Maren Bennewitz Wolfram Burgard Department of Computer Science, University of Freiburg, 7911 Freiburg, Germany

More information

Saphira Robot Control Architecture

Saphira Robot Control Architecture Saphira Robot Control Architecture Saphira Version 8.1.0 Kurt Konolige SRI International April, 2002 Copyright 2002 Kurt Konolige SRI International, Menlo Park, California 1 Saphira and Aria System Overview

More information

Last Time: Acting Humanly: The Full Turing Test

Last Time: Acting Humanly: The Full Turing Test Last Time: Acting Humanly: The Full Turing Test Alan Turing's 1950 article Computing Machinery and Intelligence discussed conditions for considering a machine to be intelligent Can machines think? Can

More information

Tracking and Formation Control of Leader-Follower Cooperative Mobile Robots Based on Trilateration Data

Tracking and Formation Control of Leader-Follower Cooperative Mobile Robots Based on Trilateration Data EMITTER International Journal of Engineering Technology Vol. 3, No. 2, December 2015 ISSN: 2443-1168 Tracking and Formation Control of Leader-Follower Cooperative Mobile Robots Based on Trilateration Data

More information

Multi Robot Localization assisted by Teammate Robots and Dynamic Objects

Multi Robot Localization assisted by Teammate Robots and Dynamic Objects Multi Robot Localization assisted by Teammate Robots and Dynamic Objects Anil Kumar Katti Department of Computer Science University of Texas at Austin akatti@cs.utexas.edu ABSTRACT This paper discusses

More information

Augmented reality approach for mobile multi robotic system development and integration

Augmented reality approach for mobile multi robotic system development and integration Augmented reality approach for mobile multi robotic system development and integration Janusz Będkowski, Andrzej Masłowski Warsaw University of Technology, Faculty of Mechatronics Warsaw, Poland Abstract

More information

Keywords Multi-Agent, Distributed, Cooperation, Fuzzy, Multi-Robot, Communication Protocol. Fig. 1. Architecture of the Robots.

Keywords Multi-Agent, Distributed, Cooperation, Fuzzy, Multi-Robot, Communication Protocol. Fig. 1. Architecture of the Robots. 1 José Manuel Molina, Vicente Matellán, Lorenzo Sommaruga Laboratorio de Agentes Inteligentes (LAI) Departamento de Informática Avd. Butarque 15, Leganés-Madrid, SPAIN Phone: +34 1 624 94 31 Fax +34 1

More information

A simple embedded stereoscopic vision system for an autonomous rover

A simple embedded stereoscopic vision system for an autonomous rover In Proceedings of the 8th ESA Workshop on Advanced Space Technologies for Robotics and Automation 'ASTRA 2004' ESTEC, Noordwijk, The Netherlands, November 2-4, 2004 A simple embedded stereoscopic vision

More information

Traffic Control for a Swarm of Robots: Avoiding Group Conflicts

Traffic Control for a Swarm of Robots: Avoiding Group Conflicts Traffic Control for a Swarm of Robots: Avoiding Group Conflicts Leandro Soriano Marcolino and Luiz Chaimowicz Abstract A very common problem in the navigation of robotic swarms is when groups of robots

More information

UChile Team Research Report 2009

UChile Team Research Report 2009 UChile Team Research Report 2009 Javier Ruiz-del-Solar, Rodrigo Palma-Amestoy, Pablo Guerrero, Román Marchant, Luis Alberto Herrera, David Monasterio Department of Electrical Engineering, Universidad de

More information

Verified Mobile Code Repository Simulator for the Intelligent Space *

Verified Mobile Code Repository Simulator for the Intelligent Space * Proceedings of the 8 th International Conference on Applied Informatics Eger, Hungary, January 27 30, 2010. Vol. 1. pp. 79 86. Verified Mobile Code Repository Simulator for the Intelligent Space * Zoltán

More information

A Reconfigurable Guidance System

A Reconfigurable Guidance System Lecture tes for the Class: Unmanned Aircraft Design, Modeling and Control A Reconfigurable Guidance System Application to Unmanned Aerial Vehicles (UAVs) y b right aileron: a2 right elevator: e 2 rudder:

More information

Autonomous Stair Climbing Algorithm for a Small Four-Tracked Robot

Autonomous Stair Climbing Algorithm for a Small Four-Tracked Robot Autonomous Stair Climbing Algorithm for a Small Four-Tracked Robot Quy-Hung Vu, Byeong-Sang Kim, Jae-Bok Song Korea University 1 Anam-dong, Seongbuk-gu, Seoul, Korea vuquyhungbk@yahoo.com, lovidia@korea.ac.kr,

More information

Distributed Virtual Environments!

Distributed Virtual Environments! Distributed Virtual Environments! Introduction! Richard M. Fujimoto! Professor!! Computational Science and Engineering Division! College of Computing! Georgia Institute of Technology! Atlanta, GA 30332-0765,

More information

Fuzzy Logic Based Robot Navigation In Uncertain Environments By Multisensor Integration

Fuzzy Logic Based Robot Navigation In Uncertain Environments By Multisensor Integration Proceedings of the 1994 IEEE International Conference on Multisensor Fusion and Integration for Intelligent Systems (MF1 94) Las Vega, NV Oct. 2-5, 1994 Fuzzy Logic Based Robot Navigation In Uncertain

More information

Behavior Emergence in Autonomous Robot Control by Means of Feedforward and Recurrent Neural Networks

Behavior Emergence in Autonomous Robot Control by Means of Feedforward and Recurrent Neural Networks Behavior Emergence in Autonomous Robot Control by Means of Feedforward and Recurrent Neural Networks Stanislav Slušný, Petra Vidnerová, Roman Neruda Abstract We study the emergence of intelligent behavior

More information

Fuzzy-Heuristic Robot Navigation in a Simulated Environment

Fuzzy-Heuristic Robot Navigation in a Simulated Environment Fuzzy-Heuristic Robot Navigation in a Simulated Environment S. K. Deshpande, M. Blumenstein and B. Verma School of Information Technology, Griffith University-Gold Coast, PMB 50, GCMC, Bundall, QLD 9726,

More information

Prof. Emil M. Petriu 17 January 2005 CEG 4392 Computer Systems Design Project (Winter 2005)

Prof. Emil M. Petriu 17 January 2005 CEG 4392 Computer Systems Design Project (Winter 2005) Project title: Optical Path Tracking Mobile Robot with Object Picking Project number: 1 A mobile robot controlled by the Altera UP -2 board and/or the HC12 microprocessor will have to pick up and drop

More information

Multi-robot Dynamic Coverage of a Planar Bounded Environment

Multi-robot Dynamic Coverage of a Planar Bounded Environment Multi-robot Dynamic Coverage of a Planar Bounded Environment Maxim A. Batalin Gaurav S. Sukhatme Robotic Embedded Systems Laboratory, Robotics Research Laboratory, Computer Science Department University

More information

ROBCHAIR - A SEMI-AUTONOMOUS WHEELCHAIR FOR DISABLED PEOPLE. G. Pires, U. Nunes, A. T. de Almeida

ROBCHAIR - A SEMI-AUTONOMOUS WHEELCHAIR FOR DISABLED PEOPLE. G. Pires, U. Nunes, A. T. de Almeida ROBCHAIR - A SEMI-AUTONOMOUS WHEELCHAIR FOR DISABLED PEOPLE G. Pires, U. Nunes, A. T. de Almeida Institute of Systems and Robotics Department of Electrical Engineering University of Coimbra, Polo II 3030

More information

Formation and Cooperation for SWARMed Intelligent Robots

Formation and Cooperation for SWARMed Intelligent Robots Formation and Cooperation for SWARMed Intelligent Robots Wei Cao 1 Yanqing Gao 2 Jason Robert Mace 3 (West Virginia University 1 University of Arizona 2 Energy Corp. of America 3 ) Abstract This article

More information

Incorporating a Software System for Robotics Control and Coordination in Mechatronics Curriculum and Research

Incorporating a Software System for Robotics Control and Coordination in Mechatronics Curriculum and Research Paper ID #15300 Incorporating a Software System for Robotics Control and Coordination in Mechatronics Curriculum and Research Dr. Maged Mikhail, Purdue University - Calumet Dr. Maged B. Mikhail, Assistant

More information

Distributed Intelligent Systems W11 Machine-Learning Methods Applied to Distributed Robotic Systems

Distributed Intelligent Systems W11 Machine-Learning Methods Applied to Distributed Robotic Systems Distributed Intelligent Systems W11 Machine-Learning Methods Applied to Distributed Robotic Systems 1 Outline Revisiting expensive optimization problems Additional experimental evidence Noise-resistant

More information