PID CONTROL FOR TWO-WHEELED INVERTED PENDULUM (WIP) SYSTEM

Size: px
Start display at page:

Download "PID CONTROL FOR TWO-WHEELED INVERTED PENDULUM (WIP) SYSTEM"

Transcription

1 PID CONTROL FOR TWO-WHEELED INVERTED PENDULUM (WIP) SYSTEM Bogdan Grămescu, Constantin Niţu, Nguyen Su Phuong Phuc, Claudia Irina Borzea University POLITEHNICA of Bucharest 313, Splaiul Independentei, Bucharest, Romania Abstract - The complexity of the inverted pendulum system has drawn the interest of many researchers around the world. Its instability feature is a good example for a control engineer, with the purpose of verifying the control theory. To verify this system, equilibrium can be maintained, being possible to do the simulation using a method with a closed loop controller, such as LQR or PID. The article presents the achievement of a two-wheeled inverted pendulum (WIP) system, having an opensource development Arduino platform as control centre, which is programmed with Processing opensource environment. With the purpose of optimizing the system operation, a Kalman filter is implemented on the Arduino platform. Keywords: Mechatronics, Inverted Pendulum, Arduino, Kalman Filter, Control Algorithm. 1. Introduction The stabilization issue has been increasingly approached in recent years, being found in a very vast application range. One of the classical stabilization control issues is the inverted pendulum. The process is nonlinear and unstable, with a single input signal and several output signals. The inverted pendulum presented in this article is a two-wheeled inverted pendulum system. The stabilization of the inverted pendulum represents a basic model for the control of other similar processes, such as: rocket takeoff, equilibration of heavy loaded cranes, etc. In recent researches, the balancing of the inverted pendulum has often been studied in the modern control theories, such as fuzzy control, variable gain control, nonlinear control and neural networks. The main goal was to design a mechatronic system consisting of an inverted pendulum articulated on the wheels axis of a two-wheeled system, with constructive solutions to correct the design errors of existent products, and to simplify the realization of a control and actuation system. 2. The structure of Two-Wheeled Inverted Pendulum (WIP) System The design principle was the following: the mechanical components consisted of LEGO components, the centre of gravity being chosen as high as possible in regard to the axis of rotatio. Figure 1: The structure of the two-wheeled inverted pendulum system Besides these components used as support, the system also consists of motors (Lego NXT with 1:48 integrated reduction gearbox and rotation transducer with 720 pulses per rotation), the Arduino Mega 2560 v3 control platform and an electronic block consisting of L298 motor driver circuit, a DC-DC convertor with 3.3V DC, and a Bluetooth HC-05 communication module for the connection with a computer system. 246 The Romanian Review Precision Mechanics, Optics & Mechatronics, 2015, Issue 48

2 Figure 2: The electronic block The control system also integrates a GY-521 sensor based on MPU This one is used to provide the necessary information to the control algorithm, regarding angles, speeds and angular accelerations. Thus, an inertial sensor had to be installed, being necessary to read the data provided by this one, but also to filter this data, in order to reduce noise and errors as much as possible. MPU-6050 is the first integrated 6 axis motion tracking device that combines a 3 axis gyroscope, a 3 axis accelerometer, and a digital motion processor (DMP), all in a small package, of 4mmx4mmx0.9mm. The values received from MPU-6050 sensor are transmitted to the Arduino development platform through I2C interface. 3. The control program implemented on the Arduino platform Starting from the mathematical model necessary for the implementation of the control algorithm, it was possible to elaborate the control program of the system, which was implemented in the Arduino Mega platform. As programming environment, the open-source Arduino software (IDE) was used, which uses Java programming language that is based on Processing open-source language. The control algorithm for the inverted pendulum system is similar to the one presented in figure 3 Figure 3: The control algorithm used for the robot The entire control process is a closed loop, the steps repeating with a predetermined frequency (figure 4). Initially, all parameters have to be declared and all the necessary conditions have to be set for the following steps. This first step of initialization is included in setup() function of the program, and is passed through once. After passing through the first step, the program will run a closed loop, at the end of each set of steps being obtained the command for each motor. The loop of the program implemented on Arduino platform is loop() function. The PWM signal for each motor is equal to the sum of the outputs of PID 1, respectively PID 2 controllers, plus the output of PID 3 controller on left motor, respectively minus the output of PID 3 controller on right motor, or vice versa. Depending on the output reference of PID 1 controller, the entire inverted pendulum structure can be controlled for moving forwards or backwards. Depending on the output reference of PID 3 controller, the structure can be controlled so that to turn or rotate. The frequency of passing through the loop is a very important factor, with direct effect on the stability level of the system. In figure 4, the main steps are presented briefly, behind whom there are various other steps such as: calibration of the signals received from sensors, filtering these signals, communication with computer, checking the battery level, etc. The Romanian Review Precision Mechanics, Optics & Mechatronics, 2015, Issue

3 Figure 4: Main processing steps of the program implemented in the Arduino platform Figure 5 presents the interface generated by the program. The upper part contains the graphics which present interest, and the bottom part contains the parameters of the three PID controllers, that can be adjusted directly from here. By means of this program, the time necessary for the control process of the robot is significantly reduced. Figure 5: The communication interface between Arduino platform and computer 248 The Romanian Review Precision Mechanics, Optics & Mechatronics, 2015, Issue 48

4 4. Implementation of Kalman filter on the Arduino platform For the statistically optimum estimation of the state of the basic system, the implementation of a Kalman filter is very useful. This algorithm uses a series of measurements observed in time, which contain noise (random variations) and other inaccuracies, and realizes estimations of the unknown variables that tend to be more accurate than the ones based on a single measurement. For the implementation of the filter on the Arduino platform, the functional model has been used, which was modified according to proper necessities. The original source code [4] belongs to Kristian Lauszus, cofounder of TKJ Electronics, an enterprise in Denmark specialized in electronic components and their applications. The implementation steps of Kalman filter are: Step 1: Predict a priori state. (1) (2) Based on this equation, the code implemented in the Arduino platform is: Step 2: Predict a priori error covariance. (3) (4) Step 3: Compute residual. (5) Step 4: Compute [S k] matrix. (6) The Romanian Review Precision Mechanics, Optics & Mechatronics, 2015, Issue

5 Step 5: Compute Kalman gain [ ]. (7) (8) In case S is a matrix, P cannot be divided by S, and therefore the inverse matrix has to be computed. Step 6: Obtain a posteriori state estimate at k moment. (9) (10) Step 7: Obtain a posteriori error covariance estimate (final step). (11) (12) A posteriori error covariance is reduced because the state estimation error has been diminished. Based on this equation, the code implemented on the Arduino platform (the following variations being chosen for most IMU) is: Instead of Kalman filter, a complementary filter can be implemented: 250 The Romanian Review Precision Mechanics, Optics & Mechatronics, 2015, Issue 48

6 where the sum of the coefficients is 1. This filter is simpler, but less accurate, providing however good results when used for simpler systems. (13) Figure 6: Graphics obtained in the following cases: unfiltered, filtered with Kalman Filter and filtered with Complementary Filter The information provided by gyroscope is integrated by time and used to update the angular position, the step by step increment being useful to prevent that the drift occurs in time, characteristic for the gyroscope. To assure enhanced disturbance sensitivity, the information from accelerometer is also used in a small amount. 5. Conclusions The equilibrium of an inverted pendulum, articulated on the wheels axis of a two wheeled system, has been successfully maintained. Between two controllers, PID and LQR, PID controller has been chosen to realize the program implemented on the Arduino platform. Kalman filter has been successfully implemented. The drift of the gyroscope was efficiently removed, so that to allow an exact estimation of the inclination angle and its drift, for the system. The program for the registration of data provided by the inertial sensor and for applying Kalman filter works properly. A greater importance is given to the fact that data from the serial port has been successfully received, and a control algorithm has been elaborated on the basis of a mathematical model, for which the program outputs have been observed depending on various inclinations and accelerations tested on the system structure, without recording abnormal values or errors. 6. References [1] Balancing a two-wheeled Autonomous Robot, Rich Chi Ooi, School of Mechanical Engineering, The University of Western Australia [2] Advance Control of Wheeled Inverted Pendulum System, Zhijun Li, College of Automation Science and Engineering, South China University of Technology, Chenguang Yang, School of Computing and Mathematics, University of Plymouth, Plymouth, Devon, UK, Liping Fan, Departament of Automation, Shanghai Jiao Tong University Shanghai, People s Republic of China [3] Sketch-for-IMU-including-Kalman-filter [4] [5] [6] NXTway-GS Model-Based Design-Control of selfbalancing two-wheeled robot built with LEGO Mindstorms NXT, Yorihisa Yamamoto, Aplication Engineering, Applied Systems First Division, CYBERNET SYSTEMS CO.,LTD. [7] Progetto e implementazione del Sistema di controllo per un pendolo inverso, Marco Triverio, Departamento di Elettronica e Informazione, Corso di Laurea in Ingegneria Informatica, Politehnico di Milano. The Romanian Review Precision Mechanics, Optics & Mechatronics, 2015, Issue

SELF-BALANCING MOBILE ROBOT TILTER

SELF-BALANCING MOBILE ROBOT TILTER Tomislav Tomašić Andrea Demetlika Prof. dr. sc. Mladen Crneković ISSN xxx-xxxx SELF-BALANCING MOBILE ROBOT TILTER Summary UDC 007.52, 62-523.8 In this project a remote controlled self-balancing mobile

More information

Extended Kalman Filtering

Extended Kalman Filtering Extended Kalman Filtering Andre Cornman, Darren Mei Stanford EE 267, Virtual Reality, Course Report, Instructors: Gordon Wetzstein and Robert Konrad Abstract When working with virtual reality, one of the

More information

ARDUINO BASED CALIBRATION OF AN INERTIAL SENSOR IN VIEW OF A GNSS/IMU INTEGRATION

ARDUINO BASED CALIBRATION OF AN INERTIAL SENSOR IN VIEW OF A GNSS/IMU INTEGRATION Journal of Young Scientist, Volume IV, 2016 ISSN 2344-1283; ISSN CD-ROM 2344-1291; ISSN Online 2344-1305; ISSN-L 2344 1283 ARDUINO BASED CALIBRATION OF AN INERTIAL SENSOR IN VIEW OF A GNSS/IMU INTEGRATION

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

Control System for a Segway

Control System for a Segway Control System for a Segway Jorge Morantes, Diana Espitia, Olguer Morales, Robinson Jiménez, Oscar Aviles Davinci Research Group, Militar Nueva Granada University, Bogotá, Colombia. Abstract In order to

More information

IMU Platform for Workshops

IMU Platform for Workshops IMU Platform for Workshops Lukáš Palkovič *, Jozef Rodina *, Peter Hubinský *3 * Institute of Control and Industrial Informatics Faculty of Electrical Engineering, Slovak University of Technology Ilkovičova

More information

Segway Robot Designing And Simulating, Using BELBIC

Segway Robot Designing And Simulating, Using BELBIC IOSR Journal of Computer Engineering (IOSR-JCE) e-issn: 2278-0661,p-ISSN: 2278-8727, Volume 18, Issue 5, Ver. II (Sept - Oct. 2016), PP 103-109 www.iosrjournals.org Segway Robot Designing And Simulating,

More information

Mechatronic demonstrator for testing sensors to be used in mobile robotics functioning on the inverted pendulum concept

Mechatronic demonstrator for testing sensors to be used in mobile robotics functioning on the inverted pendulum concept IOP Conference Series: Materials Science and Engineering PAPER OPEN ACCESS Mechatronic demonstrator for testing sensors to be used in mobile robotics functioning on the inverted pendulum concept To cite

More information

Control System Design for Tricopter using Filters and PID controller

Control System Design for Tricopter using Filters and PID controller Control System Design for Tricopter using Filters and PID controller Abstract The purpose of this paper is to present the control system design of Tricopter. We have presented the implementation of control

More information

Dynamically Adaptive Inverted Pendulum Platfom

Dynamically Adaptive Inverted Pendulum Platfom Dynamically Adaptive Inverted Pendulum Platfom 2009 Colorado Space Grant Symposium Jonathon Cox Colorado State University Undergraduate in Electrical Engineering Email: csutke@gmail.com Web: www.campusaudio.com

More information

Training Schedule. Robotic System Design using Arduino Platform

Training Schedule. Robotic System Design using Arduino Platform Training Schedule Robotic System Design using Arduino Platform Session - 1 Embedded System Design Basics : Scope : To introduce Embedded Systems hardware design fundamentals to students. Processor Selection

More information

899: DESIGN AND BUILD A BALLBOT

899: DESIGN AND BUILD A BALLBOT THE UNIVERSITY OF ADELAIDE FACULTY OF ENGINEERING, COMPUTER & MATHEMATICAL SCIENCES SCHOOL OF MECHANICAL ENGINEERING MECH ENG 435: MECHATRONICS HONOURS PROJECT 899: DESIGN AND BUILD A BALLBOT Final Report

More information

A MATHEMATICAL MODEL OF A LEGO DIFFERENTIAL DRIVE ROBOT

A MATHEMATICAL MODEL OF A LEGO DIFFERENTIAL DRIVE ROBOT 314 A MATHEMATICAL MODEL OF A LEGO DIFFERENTIAL DRIVE ROBOT Ph.D. Stud. Eng. Gheorghe GÎLCĂ, Faculty of Automation, Computers and Electronics, University of Craiova, gigi@robotics.ucv.ro Prof. Ph.D. Eng.

More information

Two Wheels Balancing Robot with Line Following Capability Nor Maniha Abdul Ghani, Faradila Naim, Tan Piow Yon

Two Wheels Balancing Robot with Line Following Capability Nor Maniha Abdul Ghani, Faradila Naim, Tan Piow Yon Two Wheels Balancing Robot with Line Following Capability Nor Maniha Abdul Ghani, Faradila Naim, Tan Piow Yon Abstract This project focuses on the development of a line follower algorithm for a Two Wheels

More information

Two Wheels Balancing Robot with Line Following Capability Nor Maniha Abdul Ghani, Faradila Naim, Tan Piow Yon

Two Wheels Balancing Robot with Line Following Capability Nor Maniha Abdul Ghani, Faradila Naim, Tan Piow Yon Two Wheels Balancing Robot with Line Following Capability Nor Maniha Abdul Ghani, Faradila Naim, Tan Piow Yon Abstract This project focuses on the development of a line follower algorithm for a Two Wheels

More information

Automatic Navigation System of Facility Agricultural Machinery Based on ZigBee

Automatic Navigation System of Facility Agricultural Machinery Based on ZigBee 4th International Conference on Sensors, Mechatronics and Automation (ICSMA 2016) Automatic Navigation System of Facility Agricultural Machinery Based on ZigBee Changming Liu1,a Jie Tian1,b,*, Shi Luo2,c

More information

Embedded Control Project -Iterative learning control for

Embedded Control Project -Iterative learning control for Embedded Control Project -Iterative learning control for Author : Axel Andersson Hariprasad Govindharajan Shahrzad Khodayari Project Guide : Alexander Medvedev Program : Embedded Systems and Engineering

More information

FLCS V2.1. AHRS, Autopilot, Gyro Stabilized Gimbals Control, Ground Control Station

FLCS V2.1. AHRS, Autopilot, Gyro Stabilized Gimbals Control, Ground Control Station AHRS, Autopilot, Gyro Stabilized Gimbals Control, Ground Control Station The platform provides a high performance basis for electromechanical system control. Originally designed for autonomous aerial vehicle

More information

Experiment on signal filter combinations for the analysis of information from inertial measurement units in AOCS

Experiment on signal filter combinations for the analysis of information from inertial measurement units in AOCS Journal of Physics: Conference Series PAPER OPEN ACCESS Experiment on signal filter combinations for the analysis of information from inertial measurement units in AOCS To cite this article: Maurício N

More information

INTERNATIONAL JOURNAL OF ELECTRICAL ENGINEERING & TECHNOLOGY (IJEET) TWO WHEELED SELF BALANCING ROBOT FOR AUTONOMOUS NAVIGATION

INTERNATIONAL JOURNAL OF ELECTRICAL ENGINEERING & TECHNOLOGY (IJEET) TWO WHEELED SELF BALANCING ROBOT FOR AUTONOMOUS NAVIGATION INTERNATIONAL JOURNAL OF ELECTRICAL ENGINEERING & TECHNOLOGY (IJEET) International Journal of Electrical Engineering and Technology (IJEET), ISSN 0976 6545(Print), ISSN 0976 6545(Print) ISSN 0976 6553(Online)

More information

Application Note. Communication between arduino and IMU Software capturing the data

Application Note. Communication between arduino and IMU Software capturing the data Application Note Communication between arduino and IMU Software capturing the data ECE 480 Team 8 Chenli Yuan Presentation Prep Date: April 8, 2013 Executive Summary In summary, this application note is

More information

Auto-Balancing Two Wheeled Inverted Pendulum Robot

Auto-Balancing Two Wheeled Inverted Pendulum Robot Available online at www.ijiere.com International Journal of Innovative and Emerging Research in Engineering e-issn: 2394 3343 p-issn: 2394 5494 Auto-Balancing Two Wheeled Inverted Pendulum Robot Om J.

More information

Design and Implementation of FPGA Based Quadcopter

Design and Implementation of FPGA Based Quadcopter Design and Implementation of FPGA Based Quadcopter G Premkumar 1 SCSVMV, Kanchipuram, Tamil Nadu, INDIA R Jayalakshmi 2 Assistant Professor, SCSVMV, Kanchipuram, Tamil Nadu, INDIA Md Akramuddin 3 Project

More information

AUTOPILOT CONTROL SYSTEM - IV

AUTOPILOT CONTROL SYSTEM - IV AUTOPILOT CONTROL SYSTEM - IV CONTROLLER The data from the inertial measurement unit is taken into the controller for processing. The input being analog requires to be passed through an ADC before being

More information

Design of a Drift Assist Control System Applied to Remote Control Car Sheng-Tse Wu, Wu-Sung Yao

Design of a Drift Assist Control System Applied to Remote Control Car Sheng-Tse Wu, Wu-Sung Yao Design of a Drift Assist Control System Applied to Remote Control Car Sheng-Tse Wu, Wu-Sung Yao International Science Index, Mechanical and Mechatronics Engineering waset.org/publication/10005017 Abstract

More information

Lab 5: Inverted Pendulum PID Control

Lab 5: Inverted Pendulum PID Control Lab 5: Inverted Pendulum PID Control In this lab we will be learning about PID (Proportional Integral Derivative) control and using it to keep an inverted pendulum system upright. We chose an inverted

More information

Introducing the Quadrotor Flying Robot

Introducing the Quadrotor Flying Robot Introducing the Quadrotor Flying Robot Roy Brewer Organizer Philadelphia Robotics Meetup Group August 13, 2009 What is a Quadrotor? A vehicle having 4 rotors (propellers) at each end of a square cross

More information

DC motor control using arduino

DC motor control using arduino DC motor control using arduino 1) Introduction: First we need to differentiate between DC motor and DC generator and where we can use it in this experiment. What is the main different between the DC-motor,

More information

MAGNETIC LEVITATION SUSPENSION CONTROL SYSTEM FOR REACTION WHEEL

MAGNETIC LEVITATION SUSPENSION CONTROL SYSTEM FOR REACTION WHEEL IMPACT: International Journal of Research in Engineering & Technology (IMPACT: IJRET) ISSN 2321-8843 Vol. 1, Issue 4, Sep 2013, 1-6 Impact Journals MAGNETIC LEVITATION SUSPENSION CONTROL SYSTEM FOR REACTION

More information

Disturbance rejection using feed-forward control system on self balancing robot

Disturbance rejection using feed-forward control system on self balancing robot Disturbance rejection using feed-forward control system on self balancing robot Barlian Henryranu Prasetio * and Wijaya Kurniawan Computer Engineering and Robotics Laboratory-Faculty of Computer Science-University

More information

Based on the ARM and PID Control Free Pendulum Balance System

Based on the ARM and PID Control Free Pendulum Balance System Available online at www.sciencedirect.com Procedia Engineering 29 (2012) 3491 3495 2012 International Workshop on Information and Electronics Engineering (IWIEE) Based on the ARM and PID Control Free Pendulum

More information

SELF-BALANCING BOT USING CONCEPT OF INVERTED PENDULUM

SELF-BALANCING BOT USING CONCEPT OF INVERTED PENDULUM SELF-BALANCING BOT USING CONCEPT OF INVERTED PENDULUM Pratyusa kumar Tripathy (109EC0427) Department of Electronics and Communication Engineering National Institute of Technology Rourkela Rourkela- 769008,India

More information

Control of motion stability of the line tracer robot using fuzzy logic and kalman filter

Control of motion stability of the line tracer robot using fuzzy logic and kalman filter Journal of Physics: Conference Series PAPER OPEN ACCESS Control of motion stability of the line tracer robot using fuzzy logic and kalman filter To cite this article: M S Novelan et al 2018 J. Phys.: Conf.

More information

Inverted Pendulum Swing Up Controller

Inverted Pendulum Swing Up Controller Dublin Institute of Technology ARROW@DIT Conference Papers School of Mechanical and Design Engineering 2011-09-29 Inverted Pendulum Swing Up Controller David Kennedy Dublin Institute of Technology, david.kennedy@dit.ie

More information

1433. A wavelet-based algorithm for numerical integration on vibration acceleration measurement data

1433. A wavelet-based algorithm for numerical integration on vibration acceleration measurement data 1433. A wavelet-based algorithm for numerical integration on vibration acceleration measurement data Dishan Huang 1, Jicheng Du 2, Lin Zhang 3, Dan Zhao 4, Lei Deng 5, Youmei Chen 6 1, 2, 3 School of Mechatronic

More information

Implementation of PIC Based Vehicle s Attitude Estimation System Using MEMS Inertial Sensors and Kalman Filter

Implementation of PIC Based Vehicle s Attitude Estimation System Using MEMS Inertial Sensors and Kalman Filter Implementation of PIC Based Vehicle s Attitude Estimation System Using MEMS Inertial Sensors and Kalman Filter Htoo Maung Maung Department of Electronic Engineering, Mandalay Technological University Mandalay,

More information

SELF STABILIZING PLATFORM

SELF STABILIZING PLATFORM SELF STABILIZING PLATFORM Shalaka Turalkar 1, Omkar Padvekar 2, Nikhil Chavan 3, Pritam Sawant 4 and Project Guide: Mr Prathamesh Indulkar 5. 1,2,3,4,5 Department of Electronics and Telecommunication,

More information

Mechatronics Engineering and Automation Faculty of Engineering, Ain Shams University MCT-151, Spring 2015 Lab-4: Electric Actuators

Mechatronics Engineering and Automation Faculty of Engineering, Ain Shams University MCT-151, Spring 2015 Lab-4: Electric Actuators Mechatronics Engineering and Automation Faculty of Engineering, Ain Shams University MCT-151, Spring 2015 Lab-4: Electric Actuators Ahmed Okasha, Assistant Lecturer okasha1st@gmail.com Objective Have a

More information

Classical Control Based Autopilot Design Using PC/104

Classical Control Based Autopilot Design Using PC/104 Classical Control Based Autopilot Design Using PC/104 Mohammed A. Elsadig, Alneelain University, Dr. Mohammed A. Hussien, Alneelain University. Abstract Many recent papers have been written in unmanned

More information

Design of Automatic Following and Locating Electric Carrier Based on Ultrasonic Positioning and PI Controller

Design of Automatic Following and Locating Electric Carrier Based on Ultrasonic Positioning and PI Controller 017 nd International Conference on Mechatronics and Information Technology (ICMIT 017) Design of Automatic Following and Locating Electric Carrier Based on Ultrasonic Positioning and PI Controller Junyang

More information

Implementing a Kalman Filter on FPGA Embedded Processor for Speed Control of a DC Motor Using Low Resolution Incremental Encoders

Implementing a Kalman Filter on FPGA Embedded Processor for Speed Control of a DC Motor Using Low Resolution Incremental Encoders , October 19-21, 2016, San Francisco, USA Implementing a Kalman Filter on FPGA Embedded Processor for Speed Control of a DC Motor Using Low Resolution Incremental Encoders Herman I. Veriñaz Jadan, Caril

More information

SRI VENKATESWARA COLLEGE OF ENGINEERING AND TECHNOLOGY

SRI VENKATESWARA COLLEGE OF ENGINEERING AND TECHNOLOGY SRI VENKATESWARA COLLEGE OF ENGINEERING AND TECHNOLOGY DEPARTMENT OF ELECTRICAL AND ELECTRONICS ENGINEERING IC 6501 CONTROL SYSTEMS UNIT I - SYSTEMS AND THEIR REPRESETNTATION` TWO MARKS QUESTIONS WITH

More information

International Journal of Advance Engineering and Research Development

International Journal of Advance Engineering and Research Development Scientific Journal of Impact Factor (SJIF): 4.14 International Journal of Advance Engineering and Research Development Volume 3, Issue 2, February -2016 e-issn (O): 2348-4470 p-issn (P): 2348-6406 SIMULATION

More information

Construction and signal filtering in Quadrotor

Construction and signal filtering in Quadrotor Construction and signal filtering in Quadrotor Arkadiusz KUBACKI, Piotr OWCZAREK, Adam OWCZARKOWSKI*, Arkadiusz JAKUBOWSKI Institute of Mechanical Technology, *Institute of Control and Information Engineering,

More information

Motion Capture for Runners

Motion Capture for Runners Motion Capture for Runners Design Team 8 - Spring 2013 Members: Blake Frantz, Zhichao Lu, Alex Mazzoni, Nori Wilkins, Chenli Yuan, Dan Zilinskas Sponsor: Air Force Research Laboratory Dr. Eric T. Vinande

More information

BEYOND TOYS. Wireless sensor extension pack. Tom Frissen s

BEYOND TOYS. Wireless sensor extension pack. Tom Frissen s LEGO BEYOND TOYS Wireless sensor extension pack Tom Frissen s040915 t.e.l.n.frissen@student.tue.nl December 2008 Faculty of Industrial Design Eindhoven University of Technology 1 2 TABLE OF CONTENT CLASS

More information

OughtToPilot. Project Report of Submission PC128 to 2008 Propeller Design Contest. Jason Edelberg

OughtToPilot. Project Report of Submission PC128 to 2008 Propeller Design Contest. Jason Edelberg OughtToPilot Project Report of Submission PC128 to 2008 Propeller Design Contest Jason Edelberg Table of Contents Project Number.. 3 Project Description.. 4 Schematic 5 Source Code. Attached Separately

More information

Design of double loop-locked system for brush-less DC motor based on DSP

Design of double loop-locked system for brush-less DC motor based on DSP International Conference on Advanced Electronic Science and Technology (AEST 2016) Design of double loop-locked system for brush-less DC motor based on DSP Yunhong Zheng 1, a 2, Ziqiang Hua and Li Ma 3

More information

Master Op-Doc/Test Plan

Master Op-Doc/Test Plan Power Supply Master Op-Doc/Test Plan Define Engineering Specs Establish battery life Establish battery technology Establish battery size Establish number of batteries Establish weight of batteries Establish

More information

Automatic Control Motion control Advanced control techniques

Automatic Control Motion control Advanced control techniques Automatic Control Motion control Advanced control techniques (luca.bascetta@polimi.it) Politecnico di Milano Dipartimento di Elettronica, Informazione e Bioingegneria Motivations (I) 2 Besides the classical

More information

Implementation of Kalman Filter on PSoC-5 Microcontroller for Mobile Robot Localization

Implementation of Kalman Filter on PSoC-5 Microcontroller for Mobile Robot Localization Journal of Communication and Computer 11(2014) 469-477 doi: 10.17265/1548-7709/2014.05 007 D DAVID PUBLISHING Implementation of Kalman Filter on PSoC-5 Microcontroller for Mobile Robot Localization Garth

More information

of an Efficient Electric

of an Efficient Electric Page00038 Abstract EVS5 Shenzhen, China, Nov 5-9, 010 Researches and Development of an Efficient Electric Personal Mover for City Commuters Cao Sijia 1, Huang Yagang 1, Zhang Youtong 1, Zhao Dong 1, Liu

More information

Sensors and Sensing Motors, Encoders and Motor Control

Sensors and Sensing Motors, Encoders and Motor Control Sensors and Sensing Motors, Encoders and Motor Control Todor Stoyanov Mobile Robotics and Olfaction Lab Center for Applied Autonomous Sensor Systems Örebro University, Sweden todor.stoyanov@oru.se 13.11.2014

More information

The Research on Servo Control System for AC PMSM Based on DSP BaiLei1, a, Wengang Zheng2, b

The Research on Servo Control System for AC PMSM Based on DSP BaiLei1, a, Wengang Zheng2, b 4th International Conference on Mechatronics, Materials, Chemistry and Computer Engineering (ICMMCCE 015) The Research on Servo Control System for AC PMSM Based on DSP BaiLei1, a, Wengang Zheng, b 1 Engineering

More information

Wheeled Mobile Robot Obstacle Avoidance Using Compass and Ultrasonic

Wheeled Mobile Robot Obstacle Avoidance Using Compass and Ultrasonic Universal Journal of Control and Automation 6(1): 13-18, 2018 DOI: 10.13189/ujca.2018.060102 http://www.hrpub.org Wheeled Mobile Robot Obstacle Avoidance Using Compass and Ultrasonic Yousef Moh. Abueejela

More information

SIMULATION OF MOVEMENT AND NAVIGATION OF LEGO NXT 2.0 MOBILE ROBOT IN UNKNOWN ENVIRONMENT INCLUDING INVERSE PENDULUM MODELING AND CONTROL

SIMULATION OF MOVEMENT AND NAVIGATION OF LEGO NXT 2.0 MOBILE ROBOT IN UNKNOWN ENVIRONMENT INCLUDING INVERSE PENDULUM MODELING AND CONTROL ANNALS of Faculty Engineering Hunedoara International Journal of Engineering Tome XIV [2016] Fascicule 1 [February] ISSN: 1584-2665 [print; online] ISSN: 1584-2673 [CD-Rom; online] a free-access multidisciplinary

More information

Modeling and Control of a Robot Arm on a Two Wheeled Moving Platform Mert Onkol 1,a, Cosku Kasnakoglu 1,b

Modeling and Control of a Robot Arm on a Two Wheeled Moving Platform Mert Onkol 1,a, Cosku Kasnakoglu 1,b Applied Mechanics and Materials Vols. 789-79 (15) pp 735-71 (15) Trans Tech Publications, Switzerland doi:1.8/www.scientific.net/amm.789-79.735 Modeling and Control of a Robot Arm on a Two Wheeled Moving

More information

Dynamic Angle Estimation

Dynamic Angle Estimation Dynamic Angle Estimation with Inertial MEMS Analog Devices Bob Scannell Mark Looney Agenda Sensor to angle basics Accelerometer basics Accelerometer behaviors Gyroscope basics Gyroscope behaviors Key factors

More information

Speed Rate Corrected Antenna Azimuth Axis Positioning System

Speed Rate Corrected Antenna Azimuth Axis Positioning System International Journal of Electronics Engineering Research. ISSN 0975-6450 Volume 9, Number 2 (2017) pp. 151-158 Research India Publications http://www.ripublication.com Speed Rate Corrected Antenna Azimuth

More information

Modeling and simulation of feed system design of CNC machine tool based on. Matlab/simulink

Modeling and simulation of feed system design of CNC machine tool based on. Matlab/simulink Modeling and simulation of feed system design of CNC machine tool based on Matlab/simulink Su-Bom Yun 1, On-Joeng Sim 2 1 2, Facaulty of machine engineering, Huichon industry university, Huichon, Democratic

More information

Dynamically Adaptive Inverted Pendulum Platform

Dynamically Adaptive Inverted Pendulum Platform Dynamically Adaptive Inverted Pendulum Platform 2009 Space Grant Symposium Jonathon Cox Colorado State University Department Of Electrical Engineering 2515 Manet Ct. Fort Collins CO, 80526 Email: csutke@gmail.com

More information

A Do-and-See Approach for Learning Mechatronics Concepts

A Do-and-See Approach for Learning Mechatronics Concepts Proceedings of the 5 th International Conference of Control, Dynamic Systems, and Robotics (CDSR'18) Niagara Falls, Canada June 7 9, 2018 Paper No. 124 DOI: 10.11159/cdsr18.124 A Do-and-See Approach for

More information

Simple Path Planning Algorithm for Two-Wheeled Differentially Driven (2WDD) Soccer Robots

Simple Path Planning Algorithm for Two-Wheeled Differentially Driven (2WDD) Soccer Robots Simple Path Planning Algorithm for Two-Wheeled Differentially Driven (2WDD) Soccer Robots Gregor Novak 1 and Martin Seyr 2 1 Vienna University of Technology, Vienna, Austria novak@bluetechnix.at 2 Institute

More information

Senior Design Project Gyroscopic Vehicle Stabilization

Senior Design Project Gyroscopic Vehicle Stabilization 2013 Senior Design Project Gyroscopic Vehicle Stabilization Group Members: Adam Dunsmoor Andrew Moser Hiral Gandhi Faculty Advisor Martin Kocanda ELE 492 4/29/2013 Table of Contents Abstract 3 Introduction

More information

Nao Devils Dortmund. Team Description for RoboCup Matthias Hofmann, Ingmar Schwarz, and Oliver Urbann

Nao Devils Dortmund. Team Description for RoboCup Matthias Hofmann, Ingmar Schwarz, and Oliver Urbann Nao Devils Dortmund Team Description for RoboCup 2014 Matthias Hofmann, Ingmar Schwarz, and Oliver Urbann Robotics Research Institute Section Information Technology TU Dortmund University 44221 Dortmund,

More information

Hybrid LQG-Neural Controller for Inverted Pendulum System

Hybrid LQG-Neural Controller for Inverted Pendulum System Hybrid LQG-Neural Controller for Inverted Pendulum System E.S. Sazonov Department of Electrical and Computer Engineering Clarkson University Potsdam, NY 13699-570 USA P. Klinkhachorn and R. L. Klein Lane

More information

1, 2, 3,

1, 2, 3, AUTOMATIC SHIP CONTROLLER USING FUZZY LOGIC Seema Singh 1, Pooja M 2, Pavithra K 3, Nandini V 4, Sahana D V 5 1 Associate Prof., Dept. of Electronics and Comm., BMS Institute of Technology and Management

More information

Sensor Data Fusion Using Kalman Filter

Sensor Data Fusion Using Kalman Filter Sensor Data Fusion Using Kalman Filter J.Z. Sasiade and P. Hartana Department of Mechanical & Aerospace Engineering arleton University 115 olonel By Drive Ottawa, Ontario, K1S 5B6, anada e-mail: jsas@ccs.carleton.ca

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

Modelling and Implementation of PID Control for Balancing of an Inverted Pendulum

Modelling and Implementation of PID Control for Balancing of an Inverted Pendulum International Journal of Automation, Control and Intelligent Systems Vol. 4, No. 4, 2018, pp. 43-53 http://www.aiscience.org/journal/ijacis ISSN: 2381-7526 (Print); ISSN: 2381-7534 (Online) Modelling and

More information

IMU: Get started with Arduino and the MPU 6050 Sensor!

IMU: Get started with Arduino and the MPU 6050 Sensor! 1 of 5 16-3-2017 15:17 IMU Interfacing Tutorial: Get started with Arduino and the MPU 6050 Sensor! By Arvind Sanjeev, Founder of DIY Hacking Arduino MPU 6050 Setup In this post, I will be reviewing a few

More information

Integration Intelligent Estimators to Disturbance Observer to Enhance Robustness of Active Magnetic Bearing Controller

Integration Intelligent Estimators to Disturbance Observer to Enhance Robustness of Active Magnetic Bearing Controller International Journal of Control Science and Engineering 217, 7(2): 25-31 DOI: 1.5923/j.control.21772.1 Integration Intelligent Estimators to Disturbance Observer to Enhance Robustness of Active Magnetic

More information

Range Sensing strategies

Range Sensing strategies Range Sensing strategies Active range sensors Ultrasound Laser range sensor Slides adopted from Siegwart and Nourbakhsh 4.1.6 Range Sensors (time of flight) (1) Large range distance measurement -> called

More information

Design of a Flight Stabilizer System and Automatic Control Using HIL Test Platform

Design of a Flight Stabilizer System and Automatic Control Using HIL Test Platform Design of a Flight Stabilizer System and Automatic Control Using HIL Test Platform Şeyma Akyürek, Gizem Sezin Özden, Emre Atlas, and Coşku Kasnakoğlu Electrical & Electronics Engineering, TOBB University

More information

CONTROL SYSTEM TO BALANCE A BIPED ROBOT BY THE SENSING OF COG TRAJECTORIES

CONTROL SYSTEM TO BALANCE A BIPED ROBOT BY THE SENSING OF COG TRAJECTORIES CONTROL SYSTEM TO BALANCE A BIPED ROBOT BY THE SENSING OF COG TRAJECTORIES Claros,Mario Jorge; Rodríguez-Ortiz, José de Jesús; Soto Rogelio Sevilla #109 Col. Altavista, Monterrey N. L. CP 64840 jorge.claros@itesm.mx,

More information

BALANCING A TWO WHEELED ROBOT

BALANCING A TWO WHEELED ROBOT University of Southern Queensland Faculty of Engineering and Surveying BALANCING A TWO WHEELED ROBOT A dissertation submitted by Kealeboga Mokonopi In fulfilment of the requirements of Courses ENG4111

More information

SELF BALANCING ROBOT. Article. 2 authors, including: Nabil Lathiff Microsoft

SELF BALANCING ROBOT. Article. 2 authors, including: Nabil Lathiff Microsoft See discussions, stats, and author profiles for this publication at: https://www.researchgate.net/publication/265227587 SELF BALANCING ROBOT Article CITATIONS 2 READS 7,256 2 authors, including: Nabil

More information

AUTONOMOUS SLAM ROBOT MECHENG 706. Group 4: Peter Sefont Tom Simson Xiting Sun Yinan Xu Date: 5 June 2016

AUTONOMOUS SLAM ROBOT MECHENG 706. Group 4: Peter Sefont Tom Simson Xiting Sun Yinan Xu Date: 5 June 2016 2016 AUTONOMOUS SLAM ROBOT MECHENG 706 Group 4: Peter Sefont Tom Simson Xiting Sun Yinan Xu Date: 5 June 2016 Executive Summary The aim of this project is to design and develop an Autonomous Simultaneous

More information

HAND GESTURE CONTROLLED ROBOT USING ARDUINO

HAND GESTURE CONTROLLED ROBOT USING ARDUINO HAND GESTURE CONTROLLED ROBOT USING ARDUINO Vrushab Sakpal 1, Omkar Patil 2, Sagar Bhagat 3, Badar Shaikh 4, Prof.Poonam Patil 5 1,2,3,4,5 Department of Instrumentation Bharati Vidyapeeth C.O.E,Kharghar,Navi

More information

Optimal Control System Design

Optimal Control System Design Chapter 6 Optimal Control System Design 6.1 INTRODUCTION The active AFO consists of sensor unit, control system and an actuator. While designing the control system for an AFO, a trade-off between the transient

More information

Intelligent Learning Control Strategies for Position Tracking of AC Servomotor

Intelligent Learning Control Strategies for Position Tracking of AC Servomotor Intelligent Learning Control Strategies for Position Tracking of AC Servomotor M.Vijayakarthick 1 1Assistant Professor& Department of Electronics and Instrumentation Engineering, Annamalai University,

More information

UNIVERSITY OF NAIROBI FACULTY OF ENGINEERING DEPARTMENT OF ELECTRICAL AND INFORMATION ENGINEERING

UNIVERSITY OF NAIROBI FACULTY OF ENGINEERING DEPARTMENT OF ELECTRICAL AND INFORMATION ENGINEERING UNIVERSITY OF NAIROBI FACULTY OF ENGINEERING DEPARTMENT OF ELECTRICAL AND INFORMATION ENGINEERING PROJECT TITLE: DESIGN AND IMPLEMENTATION OF A DIGITAL CONTROLLER FOR A WALKING ROBOT USING LEGO COMPONENTS

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

Image Recognition for PCB Soldering Platform Controlled by Embedded Microchip Based on Hopfield Neural Network

Image Recognition for PCB Soldering Platform Controlled by Embedded Microchip Based on Hopfield Neural Network 436 JOURNAL OF COMPUTERS, VOL. 5, NO. 9, SEPTEMBER Image Recognition for PCB Soldering Platform Controlled by Embedded Microchip Based on Hopfield Neural Network Chung-Chi Wu Department of Electrical Engineering,

More information

Kid-Size Humanoid Soccer Robot Design by TKU Team

Kid-Size Humanoid Soccer Robot Design by TKU Team Kid-Size Humanoid Soccer Robot Design by TKU Team Ching-Chang Wong, Kai-Hsiang Huang, Yueh-Yang Hu, and Hsiang-Min Chan Department of Electrical Engineering, Tamkang University Tamsui, Taipei, Taiwan E-mail:

More information

Sensors and Sensing Motors, Encoders and Motor Control

Sensors and Sensing Motors, Encoders and Motor Control Sensors and Sensing Motors, Encoders and Motor Control Todor Stoyanov Mobile Robotics and Olfaction Lab Center for Applied Autonomous Sensor Systems Örebro University, Sweden todor.stoyanov@oru.se 05.11.2015

More information

Automobile Prototype Servo Control

Automobile Prototype Servo Control IJIRST International Journal for Innovative Research in Science & Technology Volume 2 Issue 10 March 2016 ISSN (online): 2349-6010 Automobile Prototype Servo Control Mr. Linford William Fernandes Don Bosco

More information

Lego Mindstorms Segway Project

Lego Mindstorms Segway Project AGH - UNIVERSITY OF SCIENCE AND TECHNOLOGY Lego Mindstorms Segway Project Authors of project: Under the supervision of: Documentation drawn up by: WEBSITE: Łukasz Bondyra, Paweł Górka, Jakub Tutro, Krzysztof

More information

Hybrid Positioning through Extended Kalman Filter with Inertial Data Fusion

Hybrid Positioning through Extended Kalman Filter with Inertial Data Fusion Hybrid Positioning through Extended Kalman Filter with Inertial Data Fusion Rafiullah Khan, Francesco Sottile, and Maurizio A. Spirito Abstract In wireless sensor networks (WSNs), hybrid algorithms are

More information

Low-Cost Mobile Lab Solutions for Individualized Mechatronic Education

Low-Cost Mobile Lab Solutions for Individualized Mechatronic Education Low-Cost Mobile Lab Solutions for Individualized Mechatronic Education Joshua L. Hurst, Lecturer Department of Mechanical Aerospace and Nuclear Engineering Rensselaer Polytechnic Institute 3/13/2014 1

More information

Devastator Tank Mobile Platform with Edison SKU:ROB0125

Devastator Tank Mobile Platform with Edison SKU:ROB0125 Devastator Tank Mobile Platform with Edison SKU:ROB0125 From Robot Wiki Contents 1 Introduction 2 Tutorial 2.1 Chapter 2: Run! Devastator! 2.2 Chapter 3: Expansion Modules 2.3 Chapter 4: Build The Devastator

More information

QUADROTOR ROLL AND PITCH STABILIZATION USING SYSTEM IDENTIFICATION BASED REDESIGN OF EMPIRICAL CONTROLLERS

QUADROTOR ROLL AND PITCH STABILIZATION USING SYSTEM IDENTIFICATION BASED REDESIGN OF EMPIRICAL CONTROLLERS QUADROTOR ROLL AND PITCH STABILIZATION USING SYSTEM IDENTIFICATION BASED REDESIGN OF EMPIRICAL CONTROLLERS ANIL UFUK BATMAZ 1, a, OVUNC ELBIR 2,b and COSKU KASNAKOGLU 3,c 1,2,3 Department of Electrical

More information

Utility of Sensor Fusion of GPS and Motion Sensor in Android Devices In GPS- Deprived Environment

Utility of Sensor Fusion of GPS and Motion Sensor in Android Devices In GPS- Deprived Environment Utility of Sensor Fusion of GPS and Motion Sensor in Android Devices In GPS- Deprived Environment Amrit Karmacharya1 1 Land Management Training Center Bakhundol, Dhulikhel, Kavre, Nepal Tel:- +977-9841285489

More information

Angle Measurement on a flat Surface using High Frequency Ultrasonic Pulse

Angle Measurement on a flat Surface using High Frequency Ultrasonic Pulse I.J. Engineering and Manufacturing, 2018, 6, 26-41 Published Online November 2018 in MECS (http://www.mecs-press.net) DOI: 10.5815/ijem.2018.06.03 Available online at http://www.mecs-press.net/ijem Angle

More information

Testing Autonomous Hover Algorithms Using a Quad rotor Helicopter Test Bed

Testing Autonomous Hover Algorithms Using a Quad rotor Helicopter Test Bed Testing Autonomous Hover Algorithms Using a Quad rotor Helicopter Test Bed In conjunction with University of Washington Distributed Space Systems Lab Justin Palm Andy Bradford Andrew Nelson Milestone One

More information

TEAM AERO-I TEAM AERO-I JOURNAL PAPER DELHI TECHNOLOGICAL UNIVERSITY Journal paper for IARC 2014

TEAM AERO-I TEAM AERO-I JOURNAL PAPER DELHI TECHNOLOGICAL UNIVERSITY Journal paper for IARC 2014 TEAM AERO-I TEAM AERO-I JOURNAL PAPER DELHI TECHNOLOGICAL UNIVERSITY DELHI TECHNOLOGICAL UNIVERSITY Journal paper for IARC 2014 2014 IARC ABSTRACT The paper gives prominence to the technical details of

More information

BW-IMU200 Serials. Low-cost Inertial Measurement Unit. Technical Manual

BW-IMU200 Serials. Low-cost Inertial Measurement Unit. Technical Manual Serials Low-cost Inertial Measurement Unit Technical Manual Introduction As a low-cost inertial measurement sensor, the BW-IMU200 measures the attitude parameters of the motion carrier (roll angle, pitch

More information

istand I can Stand SPECIAL SENSOR REPORT

istand I can Stand SPECIAL SENSOR REPORT istand I can Stand SPECIAL SENSOR REPORT SUBRAT NAYAK UFID: 5095-9761 For EEL 5666 - Intelligent Machines Design Laboratory (Spring 2008) Department of Electrical and Computer Engineering University of

More information

Design and Development of Novel Two Axis Servo Control Mechanism

Design and Development of Novel Two Axis Servo Control Mechanism Design and Development of Novel Two Axis Servo Control Mechanism Shailaja Kurode, Chinmay Dharmadhikari, Mrinmay Atre, Aniruddha Katti, Shubham Shambharkar Abstract This paper presents design and development

More information