Robotics: Science and Systems

Size: px
Start display at page:

Download "Robotics: Science and Systems"

Transcription

1 Robotics: Science and Systems System Identification & Filtering Zhibin (Alex) Li School of Informatics University of Edinburgh 1

2 Outline 1. Introduction 2. Background 3. System identification 4. Signal filtering 2

3 Achieving high-level goals Adversarial actions & other agents Perception High-level goals Environment Adversarial actions & other agents Action Problem: How to generate actions, to achieve high-level goals, using limited perception and incomplete knowledge of environment (including others actions)? 3

4 Types of models Models of motion Own dynamics Object dynamics Other agents Models of environment Space & how I move in space Other navigation considerations Models of self What is the connection between my sensors and actuators? Temperature of computation/actuation system (internal state)? 4

5 Introduction 5

6 Problem solving using different models Decision Perception Action Behaviour 6

7 Types of models Focus: a mathematical model for describing the dynamic behavior of a system or process in the time/frequency domain. In robotics, models usually involve principles of physics. White-box model Grey-box model Black-box model 7

8 White-box and black-box model White-box model: a system with all necessary and a priori information available; we have knowledge of its internal structure, or the process (relationship between inputs and outputs). Black-box model: a system which can only be observed in terms of its inputs and outputs, without any knowledge of the internal mechanism. A typical black-box is the human brain. Picture is from from wikipedia author Krauss. 8

9 Grey-box model Grey-box model: a system that can be described by a partial theoretical structure and only needs data to complete the model. The exact parameter values need to be identified from data in order to be fit into the theoretical model. Most robotic systems can be represented by grey box models, as opposed to black box models (no model at all), or white box models (only theoretically exist or in simulation). Then, the remaining questions are: How to build such models? How to identify the model parameters? 9

10 Grey-box model How to build models? Answer: represent principles of physics, robotics or other subjects by using mathematical symbols (examples will be given in the following lectures). A model? A mathematical function, eg a=f/m, a simple case that relates acceleration with applied force given a known mass. How to identify the model parameters? Answer: system identification. 10

11 Example: what parameters need to be identified? A particular example: this kinematic structure is the model, where each segmental COM is located, in terms of (x, y, z) in each link, are the model parameters to identify. 11

12 Background knowledge 12

13 Linear Time-Invariant (LTI) system Linear Time-invariant (LTI) systems have two properties: 1. Linearity the relationship between the input and the output of the system follows superposition: given pairs of input-output, x1(t) y1(t), x2(t) y2(t), then a new input of c1x 1(t) + c2x2(t) will generate output of c1y1(t) + c2y2(t). 2. Time-invariance the above relationship will not change along the time, ie if we have x1(t) y1(t), then the same input applied at different time will produce the same output, x1(t-t) y1(t-t). An example of LTI is a RCL circuit (resistors, capacitors, and inductors). 13

14 Typical components in LTI systems Typically, a system receives an input signal, x(t) (generally a vector) and transforms it into the output signal, y(t). In modelling and control, this further boils down to the components as follows: u(t) is an input signal that can be manipulated (control signal) w(t) is an input signal that can be measured (measurable disturbance) v(t) is an input signal that cannot be measured (unmeasurable disturbance) y(t) is the output signal Typically, the system may also have hidden internal states 14

15 System identification 15

16 System identification System identification (SI): to build and complete mathematical models of dynamical systems from measured data. System identification involves design of experiments for collecting measurements for identifying such models, ie fitting the model parameters. Generally, we aim to formulate a model of the system from experimental results. A model is a mathematical representation that explains the observed data, and further allows us to predict the future responses of the system given the new inputs. SI is strongly related with data. 16

17 System identification A model is a purposeful simplification and abstraction of a reality. As mentioned in the first lecture, most controls or methods are model based. To build more accurate mathematical models of dynamical systems from real measurements, identification needs: First choose an appropriate model Measure the input and output signals in time or frequency domain Use an estimation method to estimate values of the parameters Evaluate the estimated model, if the model outputs data with reasonable accuracy compared to the new measurement a. b. Explain past observations Predict future observations 17

18 System identification To sum up briefly, constructing a model from data includes 3 steps: Model (first-principle) Data Criterion 18

19 To identify a system To design a controller, generally a model needs to be constructed for control purposes. Model: a representation that maps the transforms from an input to an output ^ y(t) Model Control signal u(t) Reference r(t) u(t) Controller Physical system y(t) A good model ^ matches y(t) and y(t) Disturbance d(t) Often, models are represented by differential or difference equations and used explicitly/implicitly by the control design. 19

20 Representation of a dynamical system In discrete-time form a linear time-varying, deterministic, dynamical system is represented by xt +1 = At xt + Bt ut where xt Rnx1 is a n-dimensional state vector, ut Rrx1 is an input vector, and At, Bt are matrices. Outputs of the system are functions of the state vector and are represented with a l-dimensional vector y Rlx1 yt = Ht xt where Ht Rlxn is an observation matrix. 20

21 Representation of a dynamical system A LTI dynamical system in discrete-time xt +1 = At xt + Bt ut y t = H t xt ut xt+1 Bt + Time delay of a unit xt yt Ht + At 21

22 Basics of parameter estimation Consider a simple scenario of sensor measurement: yt = Ht xt A system outputs a ground truth of variable yd (d stands for desired), but this signal is only available by sensor measurement y, which is mixed with noises. Sensor measurement y is noise-corrupted version of yd. et ut xt+1 Bt + Time delay of a unit xt yt d yt Ht + At 22

23 Basics of parameter estimation Goal: identify parameters of the sensor model Ht. Given the model structure in the form of yt = Ht xt, collect multiple measurements xt, yt, t=1,... N. So we have dataset as: y1 = H1 x1 y2 = H2 x2 yn = HN xn Note: for LTI system, H1=H2=...=HN. Stack the above equations into matrices. [y1, y2,., yn] = H * [x1, x2,., xn] 23

24 Basics of parameter estimation Let Y = [y1, y2,., yn], X=[ x1, x2,., xn], we have Y = H*X H = Y*X+ X+ is the right pseudo inverse of matrix X (X*X+=I, where I is the identity matrix). X+ = XT(X*XT)-1 Note: left pseudo inverse of matrix X is X+=(XT*X)-1XT. 24

25 The Least Square (LS) solution Solving the equation Y = H*X by H = Y*X+ using pseudo inverse X+ is a least square solution that minimizes the sum of squared errors between a model and data. In other words, H = Y*X+ is the solution that minimizes the square of the norm of vector (Y - H*X): (Y - H*X)T*(Y - H*X) See interpretation in case study To construct a model from data: 1. Model 2. Data 3. Criterion *We will learn more about least square optimization in the section of optimization later. 25

26 Case study Goal: identify parameters of the sensor model H, assuming the underlying principle is y =10*x+50, then the ground truth is H=[10, 50]. yt = Ht xt becomes [x y =[k, b]* 1], Ht=[k, b], xt=[x, 1]T; Collect multiple measurements xt, yt, t=1,... N. So we have dataset as: [ x, x,., xn [y1, y2,., yn] = Ht * 1 2 1, 1,., 1 ] Note: [x, 1]T=[x ; 1] = [x 1] 26

27 Case study [ x, x2,., xn Let Y = [y1, y2,., yn], X= 1,1 1,., 1 ], we have Y=H*X H=Y*X+ =Y*XT(X*XT)-1 X+ =XT(X*XT)-1 the right pseudo inverse of matrix X. 27

28 Case study: LS estimation x= [0:0.01:1]; e=randn(1, length(x)); y= 10*x + 50; X = [x; ones(1, length(x))]; measurement = y+e; H = measurement*x'*(x*x')^-1; yest = H*X; figure(1); hold on; set(gcf,'color','w'); plot(x,y,'r','linewidth',3) plot(x,measurement, '.', 'markersize',15) plot(x,measurement) legend('ideal','measurement'); One run of the estimated model is H = [9.8129, ] 28

29 Case study: the geometric interpretation Minimize the sum of squared errors between a model and data. What is still missing as a standard procedure for system identification? 29

30 Case study: the geometric interpretation Evaluation: how well an identified model matches the data. e = yestmeasurement mean(e) e = ydmeasurement e std(e) mean(e.^2) sum(e.^2)

31 Parameter estimation of a dynamical system The previous model of the sensor was static, which does not change with time or other parameters; then we obtained data and estimated constant parameters of the model. Apply similar procedure of estimating parameters of the model of a dynamical system system identification How to model the dynamics of a system? 31

32 Model a dynamical system: car suspension 32

33 Model abstraction A simple spring-mass-damper system M M Fs Fd m 0 (Simpfilication) 33

34 How to build a model The force applied by the spring: Correspondingly, the force by the damper: Equation of motion is (Newton s 2nd law): M M Rewrite in the form of matrix/vector, yields: Fs Fd 34

35 Parameter estimation: 2nd order dynamic system We generate a forced motion of this second order dynamic system M Data M Fs Fd Collect multiple measurements of position, velocity and acceleration Estimate the system parameters from this (hint: least square LS) 35

36 Parameter estimation: 2nd order dynamic system Recall that for each measurement, we have For a series of N measurements, 1, 2, N, construct the least square problem. 36

37 Parameter estimation: 2nd order dynamic system The stiffness k and damping c of the car suspension are identified by: 37 A similar example with real experimental data

38 Summary: model-based and model-free Model-based grey-box, because all models are the approximations of reality. Grey-box modelling: a first-principle model structure and experimental estimation of the model parameters. Model-free approach: a model may exist in reality, but is not used; or a model is too difficult to be constructed, and the system is treated as a black-box. Black-box modelling: the input-output relationship is established purely from experimental data only statistical. 38

39 Summary grey-box model and black-box model Grey-box model Black-box model Knowledge based on laws of physics and others; Physical insight and explainable; Generalization to the same type of problems Possibility of having prior simulation and study 1. High dimension of model parameters Model parameter structure can be complex, nonlinear and coupled (interdependent) Parameter tuning is challenging Represent better the real input-output behavior Convenient structure for parameter tuning Suitable for complex systems for which physical models are too difficult to build No direct implication of physical parameters or meanings No insight of its internal structure meaning no simulation of the real system until it s built. 39

40 Summary of system identification Take the equation of motion as given Perhaps from laws of physics or other domain knowledge Example is in earlier slide (a spring-mass-damper system) System model has open parameters (k, c) Measure inputs and outputs Need to do this carefully (need sufficient excitation) Obtain data of position, velocity and acceleration Estimate parameters that are unknown Least squares (specify errors, e.g., argmin (Y - H*X)T*(Y - H*X) ) 40

41 Signal filtering 41

42 Real world has uncertainties anywhere Sources of uncertainties: Models are approximations of the reality Signals are noisy, drifting Sensors have limited accuracy/resolution Environment is changing Unconsidered factors, eg temperature, humidity, illumination Lab/factory environment is more controllable, while real world is not 42

43 Why filtering? Before state estimation, we need to inspect the quality of signals first. Usually, procedure of signal filtering is required because: 1. A direct let-go of noises will jeopardize state estimation algorithm 2. Direct use of noisy signals cause instability issues in control 3. Necessary pre-filtering can reduce noise to a satisfactory level 43

44 Real world: sensory feedback is imperfect Consider a real world scenario: We have a humanoid robot Valkyrie We wish to design behaviours using visual perception First of all, we need accurate estimates of objects Stereo camera from multi-sense is like this 44

45 Why filters are needed? Signals have noises and the direct use of noisy signals cause instability issues. Necessary pre-filtering can reduce noise to a satisfactory level. Velocity signal 45

46 Common filters used in engineering Low-pass filter low frequencies lower than cut-off frequency are passed High-pass filter high frequencies higher than cut-off frequency are passed Band-pass filter only frequencies within a frequency band are passed Band-stop filter only frequencies within a frequency band are attenuated Notch filter rejects a particular frequency, eg resonance 46 Pictures of filters are adapted from from wikipedia author SpinningSpark

47 Filter effects 47

48 Common filter tools Low-pass filters are the most common ones used in practice, aim is to remove/reduce noise Occasionally, high-pass filters are needed for eliminating low frequency drifts or unwanted offset. Butterworth filter is the most commonly used. function [x_filter]=lowpass(cutoff,x, SamplingTime) samplingf=1/samplingtime; fnorm = cutoff / (samplingf/2); [b,a] = butter(3, fnorm, 'low'); x_filter = filtfilt(b, a, x); end 48

49 Example: filtering of link acceleration Case study: 1. Link encoder resolution of 19-bit; 2. 2nd order Butterworth filter, cut-off frequency of 5 Hz. Acceleration signal 49

Lecture 13 Visual Inertial Fusion

Lecture 13 Visual Inertial Fusion Lecture 13 Visual Inertial Fusion Davide Scaramuzza Course Evaluation Please fill the evaluation form you received by email! Provide feedback on Exercises: good and bad Course: good and bad How to improve

More information

Mobile Robotics. Mathematics, Models, and Methods. HI Cambridge. Alonzo Kelly. Carnegie Mellon University UNIVERSITY PRESS

Mobile Robotics. Mathematics, Models, and Methods. HI Cambridge. Alonzo Kelly. Carnegie Mellon University UNIVERSITY PRESS Mobile Robotics Mathematics, Models, and Methods Alonzo Kelly Carnegie Mellon University HI Cambridge UNIVERSITY PRESS Contents Preface page xiii 1 Introduction 1 1.1 Applications of Mobile Robots 2 1.2

More information

Inverse KKT Motion Optimization: A Newton Method to Efficiently Extract Task Spaces and Cost Parameters from Demonstrations

Inverse KKT Motion Optimization: A Newton Method to Efficiently Extract Task Spaces and Cost Parameters from Demonstrations Inverse KKT Motion Optimization: A Newton Method to Efficiently Extract Task Spaces and Cost Parameters from Demonstrations Peter Englert Machine Learning and Robotics Lab Universität Stuttgart Germany

More information

Massachusetts Institute of Technology Department of Mechanical Engineering Modeling and Simulation of Dynamic Systems

Massachusetts Institute of Technology Department of Mechanical Engineering Modeling and Simulation of Dynamic Systems INTRODUCTION GOAL OF THE SUBJECT Massachusetts Institute of Technology Department of Mechanical Engineering 2.141 Modeling and Simulation of Dynamic Systems Methods for mathematical modeling of engineering

More information

Robotics: Science and Systems

Robotics: Science and Systems Robotics: Science and Systems Model Predictive Control (MPC) Zhibin Li School of Informatics University of Edinburgh Content Concepts of MPC MPC formulation Objective function and constraints Solving the

More information

Humanoid Robotics. Least Squares. Maren Bennewitz

Humanoid Robotics. Least Squares. Maren Bennewitz Humanoid Robotics Least Squares Maren Bennewitz Goal of This Lecture Introduction into least squares Use it yourself for odometry calibration, later in the lecture: camera and whole-body self-calibration

More information

A NOUVELLE MOTION STATE-FEEDBACK CONTROL SCHEME FOR RIGID ROBOTIC MANIPULATORS

A NOUVELLE MOTION STATE-FEEDBACK CONTROL SCHEME FOR RIGID ROBOTIC MANIPULATORS A NOUVELLE MOTION STATE-FEEDBACK CONTROL SCHEME FOR RIGID ROBOTIC MANIPULATORS Ahmad Manasra, 135037@ppu.edu.ps Department of Mechanical Engineering, Palestine Polytechnic University, Hebron, Palestine

More information

Recent developments in simulation, optimization and control of flexible multibody systems

Recent developments in simulation, optimization and control of flexible multibody systems Recent developments in simulation, optimization and control of flexible multibody systems Olivier Brüls Department of Aerospace and Mechanical Engineering University of Liège o.bruls@ulg.ac.be Katholieke

More information

ES-2 Lecture: Fitting models to data

ES-2 Lecture: Fitting models to data ES-2 Lecture: Fitting models to data Outline Motivation: why fit models to data? Special case (exact solution): # unknowns in model =# datapoints Typical case (approximate solution): # unknowns in model

More information

Dealing with Scale. Stephan Weiss Computer Vision Group NASA-JPL / CalTech

Dealing with Scale. Stephan Weiss Computer Vision Group NASA-JPL / CalTech Dealing with Scale Stephan Weiss Computer Vision Group NASA-JPL / CalTech Stephan.Weiss@ieee.org (c) 2013. Government sponsorship acknowledged. Outline Why care about size? The IMU as scale provider: The

More information

Unit 2: Locomotion Kinematics of Wheeled Robots: Part 3

Unit 2: Locomotion Kinematics of Wheeled Robots: Part 3 Unit 2: Locomotion Kinematics of Wheeled Robots: Part 3 Computer Science 4766/6778 Department of Computer Science Memorial University of Newfoundland January 28, 2014 COMP 4766/6778 (MUN) Kinematics of

More information

AC : ADAPTIVE ROBOT MANIPULATORS IN GLOBAL TECHNOLOGY

AC : ADAPTIVE ROBOT MANIPULATORS IN GLOBAL TECHNOLOGY AC 2009-130: ADAPTIVE ROBOT MANIPULATORS IN GLOBAL TECHNOLOGY Alireza Rahrooh, University of Central Florida Alireza Rahrooh is aprofessor of Electrical Engineering Technology at the University of Central

More information

VIBRATION ISOLATION USING A MULTI-AXIS ROBOTIC PLATFORM G.

VIBRATION ISOLATION USING A MULTI-AXIS ROBOTIC PLATFORM G. VIBRATION ISOLATION USING A MULTI-AXIS ROBOTIC PLATFORM G. Satheesh Kumar, Y. G. Srinivasa and T. Nagarajan Precision Engineering and Instrumentation Laboratory Department of Mechanical Engineering Indian

More information

Introduction to Simulink

Introduction to Simulink University College of Southeast Norway Introduction to Simulink Hans-Petter Halvorsen, 2016.11.01 http://home.hit.no/~hansha Preface Simulink, developed by The MathWorks, is a commercial tool for modeling,

More information

ROBOTICS 01PEEQW. Basilio Bona DAUIN Politecnico di Torino

ROBOTICS 01PEEQW. Basilio Bona DAUIN Politecnico di Torino ROBOTICS 01PEEQW Basilio Bona DAUIN Politecnico di Torino Control Part 4 Other control strategies These slides are devoted to two advanced control approaches, namely Operational space control Interaction

More information

An idea which can be used once is a trick. If it can be used more than once it becomes a method

An idea which can be used once is a trick. If it can be used more than once it becomes a method An idea which can be used once is a trick. If it can be used more than once it becomes a method - George Polya and Gabor Szego University of Texas at Arlington Rigid Body Transformations & Generalized

More information

MCE/EEC 647/747: Robot Dynamics and Control. Lecture 1: Introduction

MCE/EEC 647/747: Robot Dynamics and Control. Lecture 1: Introduction MCE/EEC 647/747: Robot Dynamics and Control Lecture 1: Introduction Reading: SHV Chapter 1 Robotics and Automation Handbook, Chapter 1 Assigned readings from several articles. Cleveland State University

More information

10/11/07 1. Motion Control (wheeled robots) Representing Robot Position ( ) ( ) [ ] T

10/11/07 1. Motion Control (wheeled robots) Representing Robot Position ( ) ( ) [ ] T 3 3 Motion Control (wheeled robots) Introduction: Mobile Robot Kinematics Requirements for Motion Control Kinematic / dynamic model of the robot Model of the interaction between the wheel and the ground

More information

Relationship between Fourier Space and Image Space. Academic Resource Center

Relationship between Fourier Space and Image Space. Academic Resource Center Relationship between Fourier Space and Image Space Academic Resource Center Presentation Outline What is an image? Noise Why do we transform images? What is the Fourier Transform? Examples of images in

More information

Mechanical System and SimMechanics Simulation

Mechanical System and SimMechanics Simulation American Journal of Mechanical Engineering, 3, Vol., No. 7, 555 Available online at http://pubs.sciepub.com/ajme//7/ Science and Education Publishing DOI:.69/ajme--7 Mechanical System and SimMechanics

More information

Lecture VI: Constraints and Controllers

Lecture VI: Constraints and Controllers Lecture VI: Constraints and Controllers Motion Constraints In practice, no rigid body is free to move around on its own. Movement is constrained: wheels on a chair human body parts trigger of a gun opening

More information

Attack Resilient State Estimation for Vehicular Systems

Attack Resilient State Estimation for Vehicular Systems December 15 th 2013. T-SET Final Report Attack Resilient State Estimation for Vehicular Systems Nicola Bezzo (nicbezzo@seas.upenn.edu) Prof. Insup Lee (lee@cis.upenn.edu) PRECISE Center University of Pennsylvania

More information

SEMI-ACTIVE CONTROL OF BUILDING STRUCTURES USING A NEURO-FUZZY CONTROLLER WITH ACCELERATION FEEDBACK

SEMI-ACTIVE CONTROL OF BUILDING STRUCTURES USING A NEURO-FUZZY CONTROLLER WITH ACCELERATION FEEDBACK Proceedings of the 6th International Conference on Mechanics and Materials in Design, Editors: J.F. Silva Gomes & S.A. Meguid, P.Delgada/Azores, 26-30 July 2015 PAPER REF: 5778 SEMI-ACTIVE CONTROL OF BUILDING

More information

Motion Models (cont) 1 3/15/2018

Motion Models (cont) 1 3/15/2018 Motion Models (cont) 1 3/15/018 Computing the Density to compute,, and use the appropriate probability density function; i.e., for zeromean Gaussian noise: 3/15/018 Sampling from the Velocity Motion Model

More information

Prof. Fanny Ficuciello Robotics for Bioengineering Visual Servoing

Prof. Fanny Ficuciello Robotics for Bioengineering Visual Servoing Visual servoing vision allows a robotic system to obtain geometrical and qualitative information on the surrounding environment high level control motion planning (look-and-move visual grasping) low level

More information

FMA901F: Machine Learning Lecture 3: Linear Models for Regression. Cristian Sminchisescu

FMA901F: Machine Learning Lecture 3: Linear Models for Regression. Cristian Sminchisescu FMA901F: Machine Learning Lecture 3: Linear Models for Regression Cristian Sminchisescu Machine Learning: Frequentist vs. Bayesian In the frequentist setting, we seek a fixed parameter (vector), with value(s)

More information

Physics Tutorial 2: Numerical Integration Methods

Physics Tutorial 2: Numerical Integration Methods Physics Tutorial 2: Numerical Integration Methods Summary The concept of numerically solving differential equations is explained, and applied to real time gaming simulation. Some objects are moved in a

More information

Hand-Eye Calibration from Image Derivatives

Hand-Eye Calibration from Image Derivatives Hand-Eye Calibration from Image Derivatives Abstract In this paper it is shown how to perform hand-eye calibration using only the normal flow field and knowledge about the motion of the hand. The proposed

More information

Cecilia Laschi The BioRobotics Institute Scuola Superiore Sant Anna, Pisa

Cecilia Laschi The BioRobotics Institute Scuola Superiore Sant Anna, Pisa University of Pisa Master of Science in Computer Science Course of Robotics (ROB) A.Y. 2016/17 cecilia.laschi@santannapisa.it http://didawiki.cli.di.unipi.it/doku.php/magistraleinformatica/rob/start Robot

More information

Sensor Modalities. Sensor modality: Different modalities:

Sensor Modalities. Sensor modality: Different modalities: Sensor Modalities Sensor modality: Sensors which measure same form of energy and process it in similar ways Modality refers to the raw input used by the sensors Different modalities: Sound Pressure Temperature

More information

1. Introduction 1 2. Mathematical Representation of Robots

1. Introduction 1 2. Mathematical Representation of Robots 1. Introduction 1 1.1 Introduction 1 1.2 Brief History 1 1.3 Types of Robots 7 1.4 Technology of Robots 9 1.5 Basic Principles in Robotics 12 1.6 Notation 15 1.7 Symbolic Computation and Numerical Analysis

More information

Chapter 4 Dynamics. Part Constrained Kinematics and Dynamics. Mobile Robotics - Prof Alonzo Kelly, CMU RI

Chapter 4 Dynamics. Part Constrained Kinematics and Dynamics. Mobile Robotics - Prof Alonzo Kelly, CMU RI Chapter 4 Dynamics Part 2 4.3 Constrained Kinematics and Dynamics 1 Outline 4.3 Constrained Kinematics and Dynamics 4.3.1 Constraints of Disallowed Direction 4.3.2 Constraints of Rolling without Slipping

More information

Spatio-Temporal Stereo Disparity Integration

Spatio-Temporal Stereo Disparity Integration Spatio-Temporal Stereo Disparity Integration Sandino Morales and Reinhard Klette The.enpeda.. Project, The University of Auckland Tamaki Innovation Campus, Auckland, New Zealand pmor085@aucklanduni.ac.nz

More information

Skill. Robot/ Controller

Skill. Robot/ Controller Skill Acquisition from Human Demonstration Using a Hidden Markov Model G. E. Hovland, P. Sikka and B. J. McCarragher Department of Engineering Faculty of Engineering and Information Technology The Australian

More information

State Estimation for Continuous-Time Systems with Perspective Outputs from Discrete Noisy Time-Delayed Measurements

State Estimation for Continuous-Time Systems with Perspective Outputs from Discrete Noisy Time-Delayed Measurements State Estimation for Continuous-Time Systems with Perspective Outputs from Discrete Noisy Time-Delayed Measurements António Pedro Aguiar aguiar@ece.ucsb.edu João Pedro Hespanha hespanha@ece.ucsb.edu Dept.

More information

Quick Start Training Guide

Quick Start Training Guide Quick Start Training Guide Table of Contents 1 INTRODUCTION TO MAPLESIM... 5 1.1 USER INTERFACE... 5 2 WORKING WITH A SAMPLE MODEL... 7 2.1 RUNNING A SIMULATION... 7 2.2 GRAPHICAL OUTPUT... 7 2.3 3D VISUALIZATION...

More information

Optimal Control Techniques for Dynamic Walking

Optimal Control Techniques for Dynamic Walking Optimal Control Techniques for Dynamic Walking Optimization in Robotics & Biomechanics IWR, University of Heidelberg Presentation partly based on slides by Sebastian Sager, Moritz Diehl and Peter Riede

More information

Data-driven modeling: A low-rank approximation problem

Data-driven modeling: A low-rank approximation problem 1 / 34 Data-driven modeling: A low-rank approximation problem Ivan Markovsky Vrije Universiteit Brussel 2 / 34 Outline Setup: data-driven modeling Problems: system identification, machine learning,...

More information

Jane Li. Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute

Jane Li. Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute Jane Li Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute (3 pts) Compare the testing methods for testing path segment and finding first

More information

CSE 490R P1 - Localization using Particle Filters Due date: Sun, Jan 28-11:59 PM

CSE 490R P1 - Localization using Particle Filters Due date: Sun, Jan 28-11:59 PM CSE 490R P1 - Localization using Particle Filters Due date: Sun, Jan 28-11:59 PM 1 Introduction In this assignment you will implement a particle filter to localize your car within a known map. This will

More information

In Homework 1, you determined the inverse dynamics model of the spinbot robot to be

In Homework 1, you determined the inverse dynamics model of the spinbot robot to be Robot Learning Winter Semester 22/3, Homework 2 Prof. Dr. J. Peters, M.Eng. O. Kroemer, M. Sc. H. van Hoof Due date: Wed 6 Jan. 23 Note: Please fill in the solution on this sheet but add sheets for the

More information

Operation of machine vision system

Operation of machine vision system ROBOT VISION Introduction The process of extracting, characterizing and interpreting information from images. Potential application in many industrial operation. Selection from a bin or conveyer, parts

More information

Introduction to Simulink. The Use of Mathematic Simulations in Electrical Engineering

Introduction to Simulink. The Use of Mathematic Simulations in Electrical Engineering Introduction to Simulink The Use of Mathematic Simulations in Electrical Engineering Lecture Outline 1) Introduction to Simulink 2) Modelling of dynamics systems 2 Simulink Tool for modeling, simulating,

More information

Laser sensors. Transmitter. Receiver. Basilio Bona ROBOTICA 03CFIOR

Laser sensors. Transmitter. Receiver. Basilio Bona ROBOTICA 03CFIOR Mobile & Service Robotics Sensors for Robotics 3 Laser sensors Rays are transmitted and received coaxially The target is illuminated by collimated rays The receiver measures the time of flight (back and

More information

Tracking. Establish where an object is, other aspects of state, using time sequence Biggest problem -- Data Association

Tracking. Establish where an object is, other aspects of state, using time sequence Biggest problem -- Data Association Tracking Establish where an object is, other aspects of state, using time sequence Biggest problem -- Data Association Key ideas Tracking by detection Tracking through flow Track by detection (simple form)

More information

Flexible multibody systems - Relative coordinates approach

Flexible multibody systems - Relative coordinates approach Computer-aided analysis of multibody dynamics (part 2) Flexible multibody systems - Relative coordinates approach Paul Fisette (paul.fisette@uclouvain.be) Introduction In terms of modeling, multibody scientists

More information

Final Exam Assigned: 11/21/02 Due: 12/05/02 at 2:30pm

Final Exam Assigned: 11/21/02 Due: 12/05/02 at 2:30pm 6.801/6.866 Machine Vision Final Exam Assigned: 11/21/02 Due: 12/05/02 at 2:30pm Problem 1 Line Fitting through Segmentation (Matlab) a) Write a Matlab function to generate noisy line segment data with

More information

Nonlinear State Estimation for Robotics and Computer Vision Applications: An Overview

Nonlinear State Estimation for Robotics and Computer Vision Applications: An Overview Nonlinear State Estimation for Robotics and Computer Vision Applications: An Overview Arun Das 05/09/2017 Arun Das Waterloo Autonomous Vehicles Lab Introduction What s in a name? Arun Das Waterloo Autonomous

More information

Motor control learning and modular control architectures. Francesco Nori

Motor control learning and modular control architectures. Francesco Nori Motor control learning and modular control architectures Francesco Nori Italian Institute of Technology, Genova, ITALY Robotics Brain and Cognitive Sciences Department, (former) member of LIRA-Lab Giorgio

More information

Model Library Mechanics

Model Library Mechanics Model Library Mechanics Using the libraries Mechanics 1D (Linear), Mechanics 1D (Rotary), Modal System incl. ANSYS interface, and MBS Mechanics (3D) incl. CAD import via STL and the additional options

More information

EKF Localization and EKF SLAM incorporating prior information

EKF Localization and EKF SLAM incorporating prior information EKF Localization and EKF SLAM incorporating prior information Final Report ME- Samuel Castaneda ID: 113155 1. Abstract In the context of mobile robotics, before any motion planning or navigation algorithm

More information

Solution for Euler Equations Lagrangian and Eulerian Descriptions

Solution for Euler Equations Lagrangian and Eulerian Descriptions Solution for Euler Equations Lagrangian and Eulerian Descriptions Valdir Monteiro dos Santos Godoi valdir.msgodoi@gmail.com Abstract We find an exact solution for the system of Euler equations, following

More information

Lecture VI: Constraints and Controllers. Parts Based on Erin Catto s Box2D Tutorial

Lecture VI: Constraints and Controllers. Parts Based on Erin Catto s Box2D Tutorial Lecture VI: Constraints and Controllers Parts Based on Erin Catto s Box2D Tutorial Motion Constraints In practice, no rigid body is free to move around on its own. Movement is constrained: wheels on a

More information

III. CONCEPTS OF MODELLING II.

III. CONCEPTS OF MODELLING II. III. CONCEPTS OF MODELLING II. 5. THE MODELLING PROCEDURE 6. TYPES OF THE MODELS 7. SELECTION OF MODEL TYPE 8. SELECTION OF MODEL COMPLEXITY AND STRUCTURE 1 5. MODELLING PROCEDURE Three significant steps

More information

Practical Robotics (PRAC)

Practical Robotics (PRAC) Practical Robotics (PRAC) A Mobile Robot Navigation System (1) - Sensor and Kinematic Modelling Nick Pears University of York, Department of Computer Science December 17, 2014 nep (UoY CS) PRAC Practical

More information

Tool Center Position Determination of Deformable Sliding Star by Redundant Measurement

Tool Center Position Determination of Deformable Sliding Star by Redundant Measurement Applied and Computational Mechanics 3 (2009) 233 240 Tool Center Position Determination of Deformable Sliding Star by Redundant Measurement T. Vampola a, M. Valášek a, Z. Šika a, a Faculty of Mechanical

More information

Chapter 7. Conclusions and Future Work

Chapter 7. Conclusions and Future Work Chapter 7 Conclusions and Future Work In this dissertation, we have presented a new way of analyzing a basic building block in computer graphics rendering algorithms the computational interaction between

More information

Lecture «Robot Dynamics»: Kinematic Control

Lecture «Robot Dynamics»: Kinematic Control Lecture «Robot Dynamics»: Kinematic Control 151-0851-00 V lecture: CAB G11 Tuesday 10:15 12:00, every week exercise: HG E1.2 Wednesday 8:15 10:00, according to schedule (about every 2nd week) Marco Hutter,

More information

DEVELOPMENT OF SUBSTRUCTURED SHAKING TABLE TEST METHOD

DEVELOPMENT OF SUBSTRUCTURED SHAKING TABLE TEST METHOD DEVELOPMENT OF SUBSTRUCTURED SHAKING TABLE TEST METHOD Akira IGARASHI 1, Hirokazu IEMURA 2 And Takanori SUWA 3 SUMMARY Since various kinds of issues arise in the practical application of structural response

More information

Using RecurDyn. Contents

Using RecurDyn. Contents Using RecurDyn Contents 1.0 Multibody Dynamics Overview... 2 2.0 Multibody Dynamics Applications... 3 3.0 What is RecurDyn and how is it different?... 4 4.0 Types of RecurDyn Analysis... 5 5.0 MBD Simulation

More information

Redundancy Resolution by Minimization of Joint Disturbance Torque for Independent Joint Controlled Kinematically Redundant Manipulators

Redundancy Resolution by Minimization of Joint Disturbance Torque for Independent Joint Controlled Kinematically Redundant Manipulators 56 ICASE :The Institute ofcontrol,automation and Systems Engineering,KOREA Vol.,No.1,March,000 Redundancy Resolution by Minimization of Joint Disturbance Torque for Independent Joint Controlled Kinematically

More information

CHAPTER 3 MATHEMATICAL MODEL

CHAPTER 3 MATHEMATICAL MODEL 38 CHAPTER 3 MATHEMATICAL MODEL 3.1 KINEMATIC MODEL 3.1.1 Introduction The kinematic model of a mobile robot, represented by a set of equations, allows estimation of the robot s evolution on its trajectory,

More information

Jane Li. Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute

Jane Li. Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute Jane Li Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute What are the DH parameters for describing the relative pose of the two frames?

More information

MapleSim User's Guide

MapleSim User's Guide MapleSim User's Guide Copyright Maplesoft, a division of Waterloo Maple Inc. 2001-2009 MapleSim User's Guide Copyright Maplesoft, MapleSim, and Maple are all trademarks of Waterloo Maple Inc. Maplesoft,

More information

Neuro-fuzzy Learning of Strategies for Optimal Control Problems

Neuro-fuzzy Learning of Strategies for Optimal Control Problems Neuro-fuzzy Learning of Strategies for Optimal Control Problems Kaivan Kamali 1, Lijun Jiang 2, John Yen 1, K.W. Wang 2 1 Laboratory for Intelligent Agents 2 Structural Dynamics & Control Laboratory School

More information

LUMS Mine Detector Project

LUMS Mine Detector Project LUMS Mine Detector Project Using visual information to control a robot (Hutchinson et al. 1996). Vision may or may not be used in the feedback loop. Visual (image based) features such as points, lines

More information

Olivier Brüls. Department of Aerospace and Mechanical Engineering University of Liège

Olivier Brüls. Department of Aerospace and Mechanical Engineering University of Liège Fully coupled simulation of mechatronic and flexible multibody systems: An extended finite element approach Olivier Brüls Department of Aerospace and Mechanical Engineering University of Liège o.bruls@ulg.ac.be

More information

Motion Capture & Simulation

Motion Capture & Simulation Motion Capture & Simulation Motion Capture Character Reconstructions Joint Angles Need 3 points to compute a rigid body coordinate frame 1 st point gives 3D translation, 2 nd point gives 2 angles, 3 rd

More information

Module 1: Introduction to Finite Element Analysis. Lecture 4: Steps in Finite Element Analysis

Module 1: Introduction to Finite Element Analysis. Lecture 4: Steps in Finite Element Analysis 25 Module 1: Introduction to Finite Element Analysis Lecture 4: Steps in Finite Element Analysis 1.4.1 Loading Conditions There are multiple loading conditions which may be applied to a system. The load

More information

Using Artificial Neural Networks for Prediction Of Dynamic Human Motion

Using Artificial Neural Networks for Prediction Of Dynamic Human Motion ABSTRACT Using Artificial Neural Networks for Prediction Of Dynamic Human Motion Researchers in robotics and other human-related fields have been studying human motion behaviors to understand and mimic

More information

EXAM SOLUTIONS. Image Processing and Computer Vision Course 2D1421 Monday, 13 th of March 2006,

EXAM SOLUTIONS. Image Processing and Computer Vision Course 2D1421 Monday, 13 th of March 2006, School of Computer Science and Communication, KTH Danica Kragic EXAM SOLUTIONS Image Processing and Computer Vision Course 2D1421 Monday, 13 th of March 2006, 14.00 19.00 Grade table 0-25 U 26-35 3 36-45

More information

ME/CS 132: Introduction to Vision-based Robot Navigation! Low-level Image Processing" Larry Matthies"

ME/CS 132: Introduction to Vision-based Robot Navigation! Low-level Image Processing Larry Matthies ME/CS 132: Introduction to Vision-based Robot Navigation! Low-level Image Processing" Larry Matthies" lhm@jpl.nasa.gov, 818-354-3722" Announcements" First homework grading is done! Second homework is due

More information

Manipulator trajectory planning

Manipulator trajectory planning Manipulator trajectory planning Václav Hlaváč Czech Technical University in Prague Faculty of Electrical Engineering Department of Cybernetics Czech Republic http://cmp.felk.cvut.cz/~hlavac Courtesy to

More information

Recent developments in Real-Time Hybrid Simulation (RTHS)

Recent developments in Real-Time Hybrid Simulation (RTHS) INFRARISK- PhD Programme 2 nd Summer Workshop Recent developments in Real-Time Hybrid Simulation (RTHS) Gidewon Goitom Tekeste Laboratório Nacional de Engenharia Civil (LNEC) and University of Aveiro (UA)

More information

Structure from Motion. Prof. Marco Marcon

Structure from Motion. Prof. Marco Marcon Structure from Motion Prof. Marco Marcon Summing-up 2 Stereo is the most powerful clue for determining the structure of a scene Another important clue is the relative motion between the scene and (mono)

More information

Serial Manipulator Statics. Robotics. Serial Manipulator Statics. Vladimír Smutný

Serial Manipulator Statics. Robotics. Serial Manipulator Statics. Vladimír Smutný Serial Manipulator Statics Robotics Serial Manipulator Statics Vladimír Smutný Center for Machine Perception Czech Institute for Informatics, Robotics, and Cybernetics (CIIRC) Czech Technical University

More information

A METHOD TO MODELIZE THE OVERALL STIFFNESS OF A BUILDING IN A STICK MODEL FITTED TO A 3D MODEL

A METHOD TO MODELIZE THE OVERALL STIFFNESS OF A BUILDING IN A STICK MODEL FITTED TO A 3D MODEL A METHOD TO MODELIE THE OVERALL STIFFNESS OF A BUILDING IN A STICK MODEL FITTED TO A 3D MODEL Marc LEBELLE 1 SUMMARY The aseismic design of a building using the spectral analysis of a stick model presents

More information

Allan Variance Analysis of Random Noise Modes in Gyroscopes

Allan Variance Analysis of Random Noise Modes in Gyroscopes Allan Variance Analysis of Random Noise Modes in Gyroscopes Alexander A. Trusov, Ph.D. Alex.Trusov@gmail.com, AlexanderTrusov.com, MEMS.eng.uci.edu MicroSystems Laboratory, Mechanical and Aerospace Engineering

More information

ELEC Sensors and Actuators

ELEC Sensors and Actuators ELEC 483-001 Sensors and Actuators Text Book: SENSORS AND ACTUATORS: System Instrumentation, C. W. d e Silva, CRC Press, ISBN: 1420044834, 2007 Kalyana C. Veluvolu #IT1-817 Tel: 053-950-7232 E-mail: veluvolu@ee.knu.ac.kr

More information

Other approaches to obtaining 3D structure

Other approaches to obtaining 3D structure Other approaches to obtaining 3D structure Active stereo with structured light Project structured light patterns onto the object simplifies the correspondence problem Allows us to use only one camera camera

More information

Tutorial: Getting Started with the LabVIEW Simulation Module

Tutorial: Getting Started with the LabVIEW Simulation Module Tutorial: Getting Started with the LabVIEW Simulation Module - LabVIEW 8.5 Simulati... Page 1 of 10 Cart Help Search You are here: NI Home > Support > Product Reference > Manuals > LabVIEW 8.5 Simulation

More information

Help Page for the Java-Powered Simulation for Experimental Structural Dynamics

Help Page for the Java-Powered Simulation for Experimental Structural Dynamics Help Page for the Java-Powered Simulation for Experimental Structural Dynamics Table of Contents Introduction How to Use the Virtual Laboratory o Control Panel o Animation Panel o Response Plot Panel o

More information

Turning an Automated System into an Autonomous system using Model-Based Design Autonomous Tech Conference 2018

Turning an Automated System into an Autonomous system using Model-Based Design Autonomous Tech Conference 2018 Turning an Automated System into an Autonomous system using Model-Based Design Autonomous Tech Conference 2018 Asaf Moses Systematics Ltd., Technical Product Manager aviasafm@systematics.co.il 1 Autonomous

More information

Math 32, August 20: Review & Parametric Equations

Math 32, August 20: Review & Parametric Equations Math 3, August 0: Review & Parametric Equations Section 1: Review This course will continue the development of the Calculus tools started in Math 30 and Math 31. The primary difference between this course

More information

Adaptive Filtering using Steepest Descent and LMS Algorithm

Adaptive Filtering using Steepest Descent and LMS Algorithm IJSTE - International Journal of Science Technology & Engineering Volume 2 Issue 4 October 2015 ISSN (online): 2349-784X Adaptive Filtering using Steepest Descent and LMS Algorithm Akash Sawant Mukesh

More information

Spatial Enhancement Definition

Spatial Enhancement Definition Spatial Enhancement Nickolas Faust The Electro- Optics, Environment, and Materials Laboratory Georgia Tech Research Institute Georgia Institute of Technology Definition Spectral enhancement relies on changing

More information

Output-error model identification: linear time-invariant systems

Output-error model identification: linear time-invariant systems Output-error model identification: linear time-invariant systems Dipartimento di Scienze e Tecnologie Aerospaziali, Politecnico di Milano The OE method for LTI systems 2 For linear time-invariant systems

More information

Model-based Real-Time Estimation of Building Occupancy During Emergency Egress

Model-based Real-Time Estimation of Building Occupancy During Emergency Egress Model-based Real-Time Estimation of Building Occupancy During Emergency Egress Robert Tomastik 1, Satish Narayanan 2, Andrzej Banaszuk 3, and Sean Meyn 4 1 Pratt & Whitney 400 Main St., East Hartford,

More information

A simple example. Assume we want to find the change in the rotation angles to get the end effector to G. Effect of changing s

A simple example. Assume we want to find the change in the rotation angles to get the end effector to G. Effect of changing s CENG 732 Computer Animation This week Inverse Kinematics (continued) Rigid Body Simulation Bodies in free fall Bodies in contact Spring 2006-2007 Week 5 Inverse Kinematics Physically Based Rigid Body Simulation

More information

IVR: Open- and Closed-Loop Control. M. Herrmann

IVR: Open- and Closed-Loop Control. M. Herrmann IVR: Open- and Closed-Loop Control M. Herrmann Overview Open-loop control Feed-forward control Towards feedback control Controlling the motor over time Process model V B = k 1 s + M k 2 R ds dt Stationary

More information

Learning algorithms for physical systems: challenges and solutions

Learning algorithms for physical systems: challenges and solutions Learning algorithms for physical systems: challenges and solutions Ion Matei Palo Alto Research Center 2018 PARC 1 All Rights Reserved System analytics: how things are done Use of models (physics) to inform

More information

Simultaneous Localization and Mapping

Simultaneous Localization and Mapping Sebastian Lembcke SLAM 1 / 29 MIN Faculty Department of Informatics Simultaneous Localization and Mapping Visual Loop-Closure Detection University of Hamburg Faculty of Mathematics, Informatics and Natural

More information

Data-driven modeling: A low-rank approximation problem

Data-driven modeling: A low-rank approximation problem 1 / 31 Data-driven modeling: A low-rank approximation problem Ivan Markovsky Vrije Universiteit Brussel 2 / 31 Outline Setup: data-driven modeling Problems: system identification, machine learning,...

More information

Motion estimation of unmanned marine vehicles Massimo Caccia

Motion estimation of unmanned marine vehicles Massimo Caccia Motion estimation of unmanned marine vehicles Massimo Caccia Consiglio Nazionale delle Ricerche Istituto di Studi sui Sistemi Intelligenti per l Automazione Via Amendola 122 D/O, 70126, Bari, Italy massimo.caccia@ge.issia.cnr.it

More information

Introduction to ANSYS DesignXplorer

Introduction to ANSYS DesignXplorer Lecture 4 14. 5 Release Introduction to ANSYS DesignXplorer 1 2013 ANSYS, Inc. September 27, 2013 s are functions of different nature where the output parameters are described in terms of the input parameters

More information

1.2 Numerical Solutions of Flow Problems

1.2 Numerical Solutions of Flow Problems 1.2 Numerical Solutions of Flow Problems DIFFERENTIAL EQUATIONS OF MOTION FOR A SIMPLIFIED FLOW PROBLEM Continuity equation for incompressible flow: 0 Momentum (Navier-Stokes) equations for a Newtonian

More information

System identification from multiple short time duration signals

System identification from multiple short time duration signals System identification from multiple short time duration signals Sean Anderson Dept of Psychology, University of Sheffield www.eye-robot.org 25th October, 2007 Presentation Content Context Motor Control

More information

Inverse Kinematics of 6 DOF Serial Manipulator. Robotics. Inverse Kinematics of 6 DOF Serial Manipulator

Inverse Kinematics of 6 DOF Serial Manipulator. Robotics. Inverse Kinematics of 6 DOF Serial Manipulator Inverse Kinematics of 6 DOF Serial Manipulator Robotics Inverse Kinematics of 6 DOF Serial Manipulator Vladimír Smutný Center for Machine Perception Czech Institute for Informatics, Robotics, and Cybernetics

More information

A Modular Software Framework for Eye-Hand Coordination in Humanoid Robots

A Modular Software Framework for Eye-Hand Coordination in Humanoid Robots A Modular Software Framework for Eye-Hand Coordination in Humanoid Robots Jurgen Leitner, Simon Harding, Alexander Forster and Peter Corke Presentation: Hana Fusman Introduction/ Overview The goal of their

More information

Multiple View Geometry in Computer Vision

Multiple View Geometry in Computer Vision Multiple View Geometry in Computer Vision Prasanna Sahoo Department of Mathematics University of Louisville 1 Structure Computation Lecture 18 March 22, 2005 2 3D Reconstruction The goal of 3D reconstruction

More information