Implementation of UAV Localization Methods for a Mobile Post-Earthquake Monitoring System

Size: px
Start display at page:

Download "Implementation of UAV Localization Methods for a Mobile Post-Earthquake Monitoring System"

Transcription

1 Implementation of UAV Localization Methods for a Mobile Post-Earthquake Monitoring System Mitsuhito Hirose, Yong Xiao, Zhiyuan Zuo, Vineet R. Kamat, Dimitrios Zekkos and Jerome Lynch, Member, IEEE Department of Civil and Environmental Engineering University of Michigan, Ann Arbor, MI , USA mhirose@umich.edu, yongxiao@umich.edu, zzuo@umich.edu, vkamat@umich.edu, zekkos@umich.edu, jerlynch@umich.edu Abstract The goal of this paper is to develop an integrated mobile sensing system that enhances Unmanned Aerial Vehicles (UAV) to provide an autonomous means of locating and mapping damage characteristics of a structural system. The UAV brings mobility to the integrated sensor payload so that the sensors can access remote sites and collect data of structures and field features following an earthquake or a natural disaster. A light detection and ranging (LiDAR) sensor and high resolution camera are installed on a UAV to obtain highly detailed and accurate topological maps of physical surfaces from which structural cracks, surface chances and minor faulting can be detected. One of the challenges in automating the operation of the UAV in challenging operational environments such as GPS-denied environments (e.g., under bridges, indoor environments) is accurate navigation. In a GPS-denied environment, localization relies on on-board sensors, which has limited accuracy when positioning the UAV in a fixed coordinate system. This paper explores solutions to this problem with vision- and marker-based localization methods. The experimental results are based on a LiDAR and camera payload integrated with an octo-rotor UAV platform that has an onboard inertial measurement unit. The experimental results show that three dimensional navigation and geometric mapping in unknown operational environments are both feasible and accurate. Keywords Mobile sensors, UAV, LiDAR, localization and mapping, wireless sensor network I. INTRODUCTION In recent years, there has been growing interest in civil and commercial applications of unmanned aerial vehicles (UAVs). In particular, they have promise in being utilized to rapidly collect perishable data after natural disasters leading to improvements in post-event monitoring, assessment, and management. While UAV technology is not novel in and of itself, the rich and rapid development of flight control and autonomy through signal processing and machine learning technologies have provided a leap in the capabilities of UAVs. The development of mobile and autonomous UAVs offers an opportunity to advance natural hazard management practice, facilitating effective and accurate decision making during and after natural hazard events. This paper proposes a monitoring approach that will introduce a major paradigm-shift in how post-event site monitoring is conducted, data is disseminated, and decisions are made based on site information. Light detection and ranging (LIDAR) scans of field surfaces allow landslide topology, toppled structures, liquefied lateral spreads, and cracks to be accurately captured in a quantifiable manner that allows structural and geotechnical site characterization. Compared with previous infrastructure monitoring methods including fixed monitoring systems, the use of ground (autonomous) vehicles or human workers, comparatively less work has been devoted to the advancement of air-based robotic platforms for data collection. One of the earliest examples of the application of UAV in the field is the use of a remote controlled helicopter equipped with a camera and wireless interrogation method that could interrogate wireless sensors installed on bridges [1]. Other work includes Fumagalli, et al. [2] who proposed a UAV for performing visual inspection of complex pipe networks in power facilities. Marks, et al. [3] explored a UAV equipped with LIDAR instrumentation to inspect and map vegetation in close proximity to high voltage power lines. Jahanshahi, et al. [4] reports on pattern classification and image processing algorithms that can automatically detect cracks in civil engineering structures using high resolution camera pictures collected by UAV. Zekkos, et al. [5] reported on the feasibility of using an UAV for the autonomous acquisition of shear wave velocity measurements during reconnaissance studies following an earthquake. These previous studies have shown, in proof-of-concept manner, the potential for mobile sensing by UAVs. However, there remains more work to be done in terms of pose (position and orientation, especially the UAV yaw angle) estimation and localization of a UAV in order to fully automate the UAV operation for high resolution data collection. Many sensing tasks in infrastructure monitoring involve a GPS-denied environment (e.g. under bridges, indoor environments). In a GPS-denied environment, localization relies on on-board inertial measurement sensors, which have limited accuracy on estimating the positional state of a UAV. This project explores solutions to this problem with vision- and marker-based localization methods. The accuracy of the localization methods are evaluated based on how well a LiDAR sensor installed on a UAV can map and identify known structural geometries, including narrow-in-width surface features (such as cracks and minor faulting) with small elevation differences. II. HARDWARE/SOFTWARE SETUP A. Octo-rotor platform As shown in Fig. 1, an existing octo-rotor UAV platform (X8+ from 3D Robotics) was modified to have increased capabilities tailored for vision- and LiDAR-based localization

2 and mapping of surface geometry. The UAV was equipped with a downward-facing LiDAR instrument (Hokuyo, UTM 3LX) to map out physical objects within a 3 m range using a 18 point cloud in a 27 range oriented vertically from the bottom of the UAV. The LiDAR has a 4 Hz scanning rate. In addition, a 72p camera is mounted on a brushless gimbal (Tarot T-2D) that uses two-axis stabilization technology to ensure stable video in any flight condition. The UAV also has installed an inertial measurement unit (IMU) that employs accelerometers and gyroscopes for crude estimation of UAV position and pose. To further enhance the sensing capabilities of the UAV, an onboard navigation computing module was also installed (ODROID-U3 with an 1.7GHz ARM quad-core processor and 2 G Byte RAM from HardKernel). The on-board computer is in charge of collecting sensor data (LiDAR, camera, and IMU data) and executes a pose estimation algorithm to identify the UAV pose. The collected data is transmitted to a ground control station (GCS) through a 5 GHz WiFi interface. An autopilot system designed by the PX4 open-hardware project was installed as a flight controller of the UAV. Table 1 summarizes the detailed specifications of the extended UAV platform. B. Inter-process communications Light-weight communication and marshalling (LCM) are used for the communication of sensor data within the UAV computing architecture. LCM has an efficient broadcast mechanism using UDP multicast thereby enabling low-latency Flight controller inter-process communications. Messages can be transmitted between different processes using the publish/subscribe message passing system of LCM [6]. LCM automatically Camera Table 1. UAV platform specifications Size cm 3 Payload capacity.8 kg Vehicle weight with battery 2.5 kg Flight time 15 mins Battery 4S 14.8V 1mAh 1C Sensors on-board IMU, GPS, camera, LiDAR Flight mode Autonomous path following Altitude hold Stabilize (manual) On-board processor 1.7GHz ARM Quad-Core 2GB RAM Navigation board Flight controller LiDAR Gimbal&came Fig.1 Octo-rotor UAV with LiDAR and camera installed Ground PC ROS, LCM RC controller 2.4G 5G Wifi Fig2. System overview On board computer compiles message definition into language-specific bindings, making message language platform independent. Logging and replay functions are also available in LCM. Data collected on the onboard computer are subscribed to by the GCS so that onboard sensor data is available for debugging purpose. LCM runs on a Local Area Network to enable wireless communications between devices through a WiFi interface. ROS and MAVLink protocol were used for message passing between the flight controller and the on board computer. On board computer sends desired navigation command to the flight controller through MAVLink and collect IMU data in real-time. Fig.2 summarizes the system overview. III. MOBILE UAV LOCALIZATION UAV reconnaissance activities require knowledge of the location of the UAV relative to objects in proximity to the UAV. Position estimation (that estimates the UAV position relative to a known map given the UAV perception of its environment) is a challenging problem. This paper addresses the localization problem of a UAV using a single camera. A 72p HD resolution camera is installed on the UAV to observe a priori defined fiducial markers attached to known locations. With the help of the fiducial markers, the camera is able to measure the pose (position and orientation) of the UAV. In order to properly represent uncertainty inherent to UAV pose estimation, a Bayes recursive filter framework is used. Bayes filters are comprised of two steps: prediction and correction step as will be described in detail. A. Prediction step The prediction step uses a model of the UAV to compute a belief of the current UAV pose. As the dynamics of octo-rotors are only loosely coupled in the x, y, z and yaw angle, the UAV dynamics are modeled as four independent state variables [9]. The prediction model for filters is designed to accept the state,, of the UAV which is 8x1 and the control input vector, u, which is 4x1. Fundamentally, the control input is the linear accelerations of the octo-rotor. (1) (2) The prediction model stated in state-space form and takes measured acceleration as an input to predict the next state: (3) where (4) ROS MAVLink Pixhawk Flight controller Camera LCM UART USB USB LiDAR

3 and is the process noise modeled as Gaussian. B. Correction step Regarding the correction model, the AprilTags [7] visual fiducial system (as will be described) enables the UAV camera to measure relative position and orientation. The experiment assumes that the pose of the AprilTags with respect to the global frame is known and all fiducial AprilTags are attached on the same horizontal plane (e.g., on flat ground). Therefore the pose of the AprilTags marker m can be expressed as: (5) For the th AprilTags, the measurement obtained from the camera is expressed as follows: (6) where is the measurement noise modeled as Gaussian. A number of filter algorithms are available for utilizing these prediction and correction models for localization of the UAV. Several algorithms including optimal Gaussian filters (Kalman filter) and nonparametric filters (particle filter) were applied to perform UAV localization. C. Kalman Filter Since the prediction and observation models considered are linear, the Kalman filter was applied as a best linear unbiased estimator. The Kalman filter estimates the state of a discretetime controlled process that is governed by the linear stochastic differential equation. The discrete Kalman filter algorithm implemented is shown in Algorithm 1 below [1]. represent state vector and its covariance matrix at kth step in the prediction step, whereas represent those in the correction step. Algorithm 1 : Kalman filter 1: loop (3 Hz) 2: 3: 4: 5: 6: 7: end loop D. Particle Filter The particle filter (Algorithm 2) was implemented to the same prediction and correction model as an alternative to Gaussian-based estimation techniques. The particle filter is a more representative non-parametric filter that approximates posteriors by a finite number of values. As it is capable of representing multi-modal beliefs, the particle filter is valuable when a UAV has to cope with phases of global uncertainty or hard data association of landmarks. A low-variance sampler is used to resample particles according to weights (likelihood) of each particle [1]. is a zero-mean Gaussian likelihood probability of observing particle m given observations. Algorithm 2: Particle filter 1: loop (3 Hz) 2: for m = 1 to M (number of particles) 3: 4: 5: end for 6: 7: 8: for m = 1 to M (number of particles) // resampling 9: 1: while 11: 12: 13: end while 14: end for 15: end loop E. Vision marker calibration In order to provide position and orientation of the UAV in a correction step, a camera is mounted to observe landmarks in the environment. To provide 3D pose (position and orientation) of a camera, the visual fiducial system AprilTags [7], is used as visual landmarks of known position. AprilTags are similar to QR codes conceptually in that they are printed on paper and are composed of only black and white blocks oriented in a distinct pattern. The detection method is robust to lighting conditions and view angles even at long distances. The detection application can not only find tags in the image, but also identify the ID of the tags given their unique patterns. Moreover, with calibrated intrinsic parameters of the camera and the size of ApriTag, the camera is able to detect landmarks (identifying the ID) in the environments and also to compute the relative transformation T between the landmarks and the camera. Once the transformation matrix T between the camera and the tags are obtained, the position of the camera can be extracted from T while the orientation of the camera can be derived from T. The OpenCV computer vision library was used to calibrate the camera by taking a sufficient number of images (approximately 1) of AprilTags printed on a planar board. AprilTags detection is performed to find the tags and the corresponding corners (i.e., image points). By combining the image points and the corner points in the global coordinate frame, a calibration algorithm is carried out to find the camera matrix (projection matrix) and distortion coefficient of the camera. The Kalman filter algorithm and the vision observation algorithm was tested in a simple environment with 1 fiducial tags. The frame rate was set at 3 fps and the UAV based camera was moved along an eight-shaped trajectory on an x-y plane. Fig.3 shows the result of tracking the position of the camera. Note that position and velocity noise was assumed to be independent. The variance of motion noise corresponding to position was set to.1 while that of velocity was set as.1.

4 z position [m] Kalman Filter original observation the University of Michigan. The dimension of the cage is roughly 4.57 m wide, m long, and 5.49 m high; the cage is fully enclosed on all sides. In the experimental area, there exist a structures (i.e., a floating tank) which can be used for evaluating the 3D reconstruction of the LiDAR data obtained from the UAV. In addition, about 5 fiducial markers are attached to the ground in a U-shape around the structure. Tag locations are measured by measurement tape to obtain a precise location for each Fig. 3 Trajectory of the camera using Kalman filtering (blue squares denote AprilTag locations) z position [m] y position [m] Particle Filter original observation y position [m] x position [m] x position [m] B. Localization results In this experiment, the UAV acquired data has different sampling rates. The IMU sampling rate is 1 Hz, the camera frame rate is 3 Hz, and the LiDAR scan rate is 4 Hz. Each data stream was interpolated so that the pose estimation algorithm can run at 6 Hz. Fig.7 shows the KF filter results on a subset of the data; the total data contains 1, images and a subset was used for visualization and experiments. Based on a comparison of the KF trajectory and the initial trajectory estimated by the camera, it is concluded that the KF filter is able to provide a smooth and stable set of UAV poses. It is also shown that when only using the camera, the pose estimation is not smooth because of motion blur and the low resolution of the camera. When the UAV flies at above a certain speed, motion blur occurs and the camera will lose some of the tags as a result. As the number of tags detected changes, accuracy and resolution of the vision-based localization fluctuates in tandem. Regarding the flying height of the UAV, when the flying height Fig. 4 Trajectory of the camera using particle filtering (blue squares denote AprilTag locations) This allows more flexibility to a constant velocity model assumed in the prediction step. Measurement noise variance was set as 1 for each x, y, and z observations. This gives more belief on the prediction model and smooth out the errors of observation of the fiducial markers. Fig. 3 shows that the Kalman filter (KF) gives a better estimation of the pose trajectory of a camera. Note that the blue squares in the figure represent coordinates of the fiducial tags. Fig. 4 shows the same result but when using the particle filter (PF) algorithm. The number of particles was set to 8. The observation noise covariance was set as an identity matrix of magnitude.1. Motion noise was again assumed to be independent and variance corresponding to the y-direction was set as.1. The other portion of motion noise variance was set as.1. Fig. 5 Concept figure of the geometric mapping task IV. EXPERIMENTS A. Experimental Setup Fig. 5 shows the overall concept of the experiments. Firstly, the UAV collects data from its camera and IMU. This data is then used as input to the KF algorithm for pose estimation. This estimated UAV trajectory is utilized for registering the location and pose of the UAV LiDAR. To simulate an indoor GPSdenied environment, a net-caged area (Fig. 6) was constructed in a hydraulic laboratory (i.e., wave tank) with high ceilings at Fig. 6 Flying environment in the lab

5 and it does not provide the information of the UAV along its flying direction, the ICP method is employed to correct the x and z of successive scans. Fig. 1 shows the original point clouds before correction from the top view. 2D scans are lined side by side in order but there are significant distortions due to changes in the UAV pose. Fig. 11 shows the same scan lined in order but correct by the ICP algorithm in terms of x and z direction. Compared to the original point clouds in Fig. 1, it is shown that ICP corrects distortion of point clouds in x and z directions. Outlier points are due to the meshed net of the UAV cage (i.e., some laser emission light went through holes of mesh net). Fig. 7 KF estimated (blue) versus camera estimated (red) trajectories Fig.8 Tag detection performance (at an altitude of 4.8 m) Fig.1 Original point clouds (top view) Fig.9 Tag detection performance (at a low altitude of 3 m) of the UAV is greater than 5m, the camera will detect less tags compared to flying at a lower height (e.g. 3m) because of the image resolution of each tag. Therefore, the UAV flies at a lower height in collecting the data. Fig. 8 and Fig. 9 show the performance of the tag detection algorithm when the UAV flies at a high altitude and at a low altitude, respectively. When high, 9 out of 16 tags are detected while 11 out of 11 are detected when low. C. Iterative Closest Point (ICP) The ICP algorithm (Algorithm 3, 4) is usually utilized for estimating the 3D rotational and translation matrix between two LiDAR scans. However, since the laser can only get 2D scans Fig.11 ICP-corrected point clouds (top view) Algorithm 3: LiDAR 2D scan registration 1: 2: 3: for : endfor 5: return for

6 Algorithm 4: ICP for 2D scan 1: for 2: Initial transformation for k and k+1 scan 3: Iterative procedure to converge to local minima 1. find closest point 2. Transform, to minimize between each and 3. Terminate when change in error falls below a the preset threshold 4: Choose the best and for different initializations 5: endfor 6: Return and for D. Digital Terrain Model with LiDAR The LiDAR on the UAV presents a 2D-planar scan of space by measuring the phase lag of the returned light signal. The LiDAR generates 18 points per rotation. These points are mapped from the pose of the UAV utilizing range and angle information. The camera channel and LiDAR channel each published time stamps along with the data so that pose of the UAV and LiDAR data can be synchronized. Fig. 12 shows a result of reconstruction of airborne LIDAR data collected by the UAV. Each 2D planar scan point is projected and mapped based on the estimated location of the UAV. 3D geometric models were reconstructed from the LIDAR data; these images captured the general geometry of the target structure well. ACKNOWLEDGMENT The authors would like to acknowledge the funding provided by the National Science Foundation under Grant Numbers CMMI , CMMI , and CMMI REFERENCES [1] Taylor, Stuart G., Farinholt, K. M., Flynn, E. B., Figueiredo, E., Mascarenas, D. L., Moro, E. A., Park, G., Todd, M. D., Farrar, C. R., "A mobile-agent-based wireless sensing network for structural monitoring applications." Measurement Science and Technology 2(4): 4521, 29. [2] Keemink, A. Q. L., Fumagalli, M., Stramigioli, S., Carloni, R. "Mechanical design of a manipulation system for unmanned aerial vehicles." 212 IEEE International Conference on Robotics and Automation (ICRA), IEEE, 212. [3] Ax, M., Thamke, S., Kuhnert, L., Kuhnert, K. D., "UAV based laser measurement for vegetation control at high-voltage transmission lines." Advanced Materials Research. 614(1): , 213. [4] Jahanshahi, M. R., Masri, S., Padgett, C. W., Sukhatme, G. S., "An innovative methodology for detection and quantification of cracks through incorporation of depth perception." Machine Vision and Applications, 24(2): , 213. [5] Zekkos, D., Lynch, J. P., Sahadewa, A., Hirose, M., and Ellis, D. "Proofof-Concept Shear Wave Velocity Measurements Using an Unmanned Autonomous Aerial Vehicle." Geo-Congress, Atlanta, GA, 214. [6] Huang, A.S., Olson, E., Moore, D. C., "LCM: Lightweight Communications and Marshalling," 21 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Taipei, Taiwan, 21. [7] Olson E. AprilTag: A robust and flexible visual fiducial system, 211 IEEE International Conference on Robotics and Automation (ICRA), Shanghai, China, pp. 34-7, 211. [8] Benini, A., Mancini, A., Longhi, S. An IMU/UWB/Vision-based Extended Kalman Filter for Mini-UAV Localization in Indoor Environment using a Wireless Sensor Network, Journal of Intelligent & Robotic Systems, 7(1-4): , 213. [9] Meier, L., Tanskanen, P., Fraundorfer, F., Pollefeys, M., PIXHAWK: A system for Autonomous Flight using Onboard Computer Vision, 211 IEEE International Conference on Robotics and Automation (ICRA), Shanghai, China, pp , 211. [1] Thrun, S., and Burgard, W. Probabilistic Robotics. Cambridge, Mass.: MIT Press, 25. Fig.12 LiDAR data reconstruction V. CONCLUSIONS The paper has shown that UAVs are capable of implementing a LiDAR-based structural health monitoring system in a GPS-denied environment following a natural disaster. The localization algorithm implemented successfully register LiDAR scan data to reconstruct geometric feature of surrounding environment of the UAV. Future works include mapping of the unknown landmarks by SLAM methods and developing damage classification algorithm based on LiDAR point clouds data.

Marker Based Localization of a Quadrotor. Akshat Agarwal & Siddharth Tanwar

Marker Based Localization of a Quadrotor. Akshat Agarwal & Siddharth Tanwar Marker Based Localization of a Quadrotor Akshat Agarwal & Siddharth Tanwar Objective Introduction Objective: To implement a high level control pipeline on a quadrotor which could autonomously take-off,

More information

MULTI-MODAL MAPPING. Robotics Day, 31 Mar Frank Mascarich, Shehryar Khattak, Tung Dang

MULTI-MODAL MAPPING. Robotics Day, 31 Mar Frank Mascarich, Shehryar Khattak, Tung Dang MULTI-MODAL MAPPING Robotics Day, 31 Mar 2017 Frank Mascarich, Shehryar Khattak, Tung Dang Application-Specific Sensors Cameras TOF Cameras PERCEPTION LiDAR IMU Localization Mapping Autonomy Robotic Perception

More information

Efficient SLAM Scheme Based ICP Matching Algorithm Using Image and Laser Scan Information

Efficient SLAM Scheme Based ICP Matching Algorithm Using Image and Laser Scan Information Proceedings of the World Congress on Electrical Engineering and Computer Systems and Science (EECSS 2015) Barcelona, Spain July 13-14, 2015 Paper No. 335 Efficient SLAM Scheme Based ICP Matching Algorithm

More information

Lecture: Autonomous micro aerial vehicles

Lecture: Autonomous micro aerial vehicles Lecture: Autonomous micro aerial vehicles Friedrich Fraundorfer Remote Sensing Technology TU München 1/41 Autonomous operation@eth Zürich Start 2/41 Autonomous operation@eth Zürich 3/41 Outline MAV system

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

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

Overview. EECS 124, UC Berkeley, Spring 2008 Lecture 23: Localization and Mapping. Statistical Models

Overview. EECS 124, UC Berkeley, Spring 2008 Lecture 23: Localization and Mapping. Statistical Models Introduction ti to Embedded dsystems EECS 124, UC Berkeley, Spring 2008 Lecture 23: Localization and Mapping Gabe Hoffmann Ph.D. Candidate, Aero/Astro Engineering Stanford University Statistical Models

More information

Autonomous Mobile Robot Design

Autonomous Mobile Robot Design Autonomous Mobile Robot Design Topic: EKF-based SLAM Dr. Kostas Alexis (CSE) These slides have partially relied on the course of C. Stachniss, Robot Mapping - WS 2013/14 Autonomous Robot Challenges Where

More information

Robot Localization based on Geo-referenced Images and G raphic Methods

Robot Localization based on Geo-referenced Images and G raphic Methods Robot Localization based on Geo-referenced Images and G raphic Methods Sid Ahmed Berrabah Mechanical Department, Royal Military School, Belgium, sidahmed.berrabah@rma.ac.be Janusz Bedkowski, Łukasz Lubasiński,

More information

Personal Navigation and Indoor Mapping: Performance Characterization of Kinect Sensor-based Trajectory Recovery

Personal Navigation and Indoor Mapping: Performance Characterization of Kinect Sensor-based Trajectory Recovery Personal Navigation and Indoor Mapping: Performance Characterization of Kinect Sensor-based Trajectory Recovery 1 Charles TOTH, 1 Dorota BRZEZINSKA, USA 2 Allison KEALY, Australia, 3 Guenther RETSCHER,

More information

Graph-based SLAM (Simultaneous Localization And Mapping) for Bridge Inspection Using UAV (Unmanned Aerial Vehicle)

Graph-based SLAM (Simultaneous Localization And Mapping) for Bridge Inspection Using UAV (Unmanned Aerial Vehicle) Graph-based SLAM (Simultaneous Localization And Mapping) for Bridge Inspection Using UAV (Unmanned Aerial Vehicle) Taekjun Oh 1), Sungwook Jung 2), Seungwon Song 3), and Hyun Myung 4) 1), 2), 3), 4) Urban

More information

Tightly-Integrated Visual and Inertial Navigation for Pinpoint Landing on Rugged Terrains

Tightly-Integrated Visual and Inertial Navigation for Pinpoint Landing on Rugged Terrains Tightly-Integrated Visual and Inertial Navigation for Pinpoint Landing on Rugged Terrains PhD student: Jeff DELAUNE ONERA Director: Guy LE BESNERAIS ONERA Advisors: Jean-Loup FARGES Clément BOURDARIAS

More information

LOAM: LiDAR Odometry and Mapping in Real Time

LOAM: LiDAR Odometry and Mapping in Real Time LOAM: LiDAR Odometry and Mapping in Real Time Aayush Dwivedi (14006), Akshay Sharma (14062), Mandeep Singh (14363) Indian Institute of Technology Kanpur 1 Abstract This project deals with online simultaneous

More information

3D Terrain Sensing System using Laser Range Finder with Arm-Type Movable Unit

3D Terrain Sensing System using Laser Range Finder with Arm-Type Movable Unit 3D Terrain Sensing System using Laser Range Finder with Arm-Type Movable Unit 9 Toyomi Fujita and Yuya Kondo Tohoku Institute of Technology Japan 1. Introduction A 3D configuration and terrain sensing

More information

Vehicle Localization. Hannah Rae Kerner 21 April 2015

Vehicle Localization. Hannah Rae Kerner 21 April 2015 Vehicle Localization Hannah Rae Kerner 21 April 2015 Spotted in Mtn View: Google Car Why precision localization? in order for a robot to follow a road, it needs to know where the road is to stay in a particular

More information

Unmanned Aerial Vehicles

Unmanned Aerial Vehicles Unmanned Aerial Vehicles Embedded Control Edited by Rogelio Lozano WILEY Table of Contents Chapter 1. Aerodynamic Configurations and Dynamic Models 1 Pedro CASTILLO and Alejandro DZUL 1.1. Aerodynamic

More information

ROBOT TEAMS CH 12. Experiments with Cooperative Aerial-Ground Robots

ROBOT TEAMS CH 12. Experiments with Cooperative Aerial-Ground Robots ROBOT TEAMS CH 12 Experiments with Cooperative Aerial-Ground Robots Gaurav S. Sukhatme, James F. Montgomery, and Richard T. Vaughan Speaker: Jeff Barnett Paper Focus Heterogeneous Teams for Surveillance

More information

Low Cost solution for Pose Estimation of Quadrotor

Low Cost solution for Pose Estimation of Quadrotor Low Cost solution for Pose Estimation of Quadrotor mangal@iitk.ac.in https://www.iitk.ac.in/aero/mangal/ Intelligent Guidance and Control Laboratory Indian Institute of Technology, Kanpur Mangal Kothari

More information

Computationally Efficient Visual-inertial Sensor Fusion for GPS-denied Navigation on a Small Quadrotor

Computationally Efficient Visual-inertial Sensor Fusion for GPS-denied Navigation on a Small Quadrotor Computationally Efficient Visual-inertial Sensor Fusion for GPS-denied Navigation on a Small Quadrotor Chang Liu & Stephen D. Prior Faculty of Engineering and the Environment, University of Southampton,

More information

Visual SLAM for small Unmanned Aerial Vehicles

Visual SLAM for small Unmanned Aerial Vehicles Visual SLAM for small Unmanned Aerial Vehicles Margarita Chli Autonomous Systems Lab, ETH Zurich Simultaneous Localization And Mapping How can a body navigate in a previously unknown environment while

More information

Sensor Fusion: Potential, Challenges and Applications. Presented by KVH Industries and Geodetics, Inc. December 2016

Sensor Fusion: Potential, Challenges and Applications. Presented by KVH Industries and Geodetics, Inc. December 2016 Sensor Fusion: Potential, Challenges and Applications Presented by KVH Industries and Geodetics, Inc. December 2016 1 KVH Industries Overview Innovative technology company 600 employees worldwide Focused

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

Calibration of a rotating multi-beam Lidar

Calibration of a rotating multi-beam Lidar The 2010 IEEE/RSJ International Conference on Intelligent Robots and Systems October 18-22, 2010, Taipei, Taiwan Calibration of a rotating multi-beam Lidar Naveed Muhammad 1,2 and Simon Lacroix 1,2 Abstract

More information

Where s the Boss? : Monte Carlo Localization for an Autonomous Ground Vehicle using an Aerial Lidar Map

Where s the Boss? : Monte Carlo Localization for an Autonomous Ground Vehicle using an Aerial Lidar Map Where s the Boss? : Monte Carlo Localization for an Autonomous Ground Vehicle using an Aerial Lidar Map Sebastian Scherer, Young-Woo Seo, and Prasanna Velagapudi October 16, 2007 Robotics Institute Carnegie

More information

Autonomous Navigation in Complex Indoor and Outdoor Environments with Micro Aerial Vehicles

Autonomous Navigation in Complex Indoor and Outdoor Environments with Micro Aerial Vehicles Autonomous Navigation in Complex Indoor and Outdoor Environments with Micro Aerial Vehicles Shaojie Shen Dept. of Electrical and Systems Engineering & GRASP Lab, University of Pennsylvania Committee: Daniel

More information

Pose Estimation and Control of Micro-Air Vehicles

Pose Estimation and Control of Micro-Air Vehicles Pose Estimation and Control of Micro-Air Vehicles IVAN DRYANOVSKI, Ph.D. Candidate, Computer Science ROBERTO G. VALENTI, Ph.D. Candidate, Electrical Engineering Mentor: JIZHONG XIAO, Professor, Electrical

More information

Autonomous Navigation for Flying Robots

Autonomous Navigation for Flying Robots Computer Vision Group Prof. Daniel Cremers Autonomous Navigation for Flying Robots Lecture 7.2: Visual Odometry Jürgen Sturm Technische Universität München Cascaded Control Robot Trajectory 0.1 Hz Visual

More information

Camera Drones Lecture 2 Control and Sensors

Camera Drones Lecture 2 Control and Sensors Camera Drones Lecture 2 Control and Sensors Ass.Prof. Friedrich Fraundorfer WS 2017 1 Outline Quadrotor control principles Sensors 2 Quadrotor control - Hovering Hovering means quadrotor needs to hold

More information

Revising Stereo Vision Maps in Particle Filter Based SLAM using Localisation Confidence and Sample History

Revising Stereo Vision Maps in Particle Filter Based SLAM using Localisation Confidence and Sample History Revising Stereo Vision Maps in Particle Filter Based SLAM using Localisation Confidence and Sample History Simon Thompson and Satoshi Kagami Digital Human Research Center National Institute of Advanced

More information

Aerial and Ground-based Collaborative Mapping: An Experimental Study

Aerial and Ground-based Collaborative Mapping: An Experimental Study Aerial and Ground-based Collaborative Mapping: An Experimental Study Ji Zhang and Sanjiv Singh Abstract We here present studies to enable aerial and ground-based collaborative mapping in GPS-denied environments.

More information

Stable Vision-Aided Navigation for Large-Area Augmented Reality

Stable Vision-Aided Navigation for Large-Area Augmented Reality Stable Vision-Aided Navigation for Large-Area Augmented Reality Taragay Oskiper, Han-Pang Chiu, Zhiwei Zhu Supun Samarasekera, Rakesh Teddy Kumar Vision and Robotics Laboratory SRI-International Sarnoff,

More information

Evaluating the Performance of a Vehicle Pose Measurement System

Evaluating the Performance of a Vehicle Pose Measurement System Evaluating the Performance of a Vehicle Pose Measurement System Harry Scott Sandor Szabo National Institute of Standards and Technology Abstract A method is presented for evaluating the performance of

More information

Introduction to Mobile Robotics Bayes Filter Particle Filter and Monte Carlo Localization. Wolfram Burgard

Introduction to Mobile Robotics Bayes Filter Particle Filter and Monte Carlo Localization. Wolfram Burgard Introduction to Mobile Robotics Bayes Filter Particle Filter and Monte Carlo Localization Wolfram Burgard 1 Motivation Recall: Discrete filter Discretize the continuous state space High memory complexity

More information

Aerial Robotic Autonomous Exploration & Mapping in Degraded Visual Environments. Kostas Alexis Autonomous Robots Lab, University of Nevada, Reno

Aerial Robotic Autonomous Exploration & Mapping in Degraded Visual Environments. Kostas Alexis Autonomous Robots Lab, University of Nevada, Reno Aerial Robotic Autonomous Exploration & Mapping in Degraded Visual Environments Kostas Alexis Autonomous Robots Lab, University of Nevada, Reno Motivation Aerial robotic operation in GPS-denied Degraded

More information

Segmentation and Tracking of Partial Planar Templates

Segmentation and Tracking of Partial Planar Templates Segmentation and Tracking of Partial Planar Templates Abdelsalam Masoud William Hoff Colorado School of Mines Colorado School of Mines Golden, CO 800 Golden, CO 800 amasoud@mines.edu whoff@mines.edu Abstract

More information

POTENTIAL ACTIVE-VISION CONTROL SYSTEMS FOR UNMANNED AIRCRAFT

POTENTIAL ACTIVE-VISION CONTROL SYSTEMS FOR UNMANNED AIRCRAFT 26 TH INTERNATIONAL CONGRESS OF THE AERONAUTICAL SCIENCES POTENTIAL ACTIVE-VISION CONTROL SYSTEMS FOR UNMANNED AIRCRAFT Eric N. Johnson* *Lockheed Martin Associate Professor of Avionics Integration, Georgia

More information

Autonomous Landing of an Unmanned Aerial Vehicle

Autonomous Landing of an Unmanned Aerial Vehicle Autonomous Landing of an Unmanned Aerial Vehicle Joel Hermansson, Andreas Gising Cybaero AB SE-581 12 Linköping, Sweden Email: {joel.hermansson, andreas.gising}@cybaero.se Martin Skoglund and Thomas B.

More information

Humanoid Robotics. Monte Carlo Localization. Maren Bennewitz

Humanoid Robotics. Monte Carlo Localization. Maren Bennewitz Humanoid Robotics Monte Carlo Localization Maren Bennewitz 1 Basis Probability Rules (1) If x and y are independent: Bayes rule: Often written as: The denominator is a normalizing constant that ensures

More information

Exterior Orientation Parameters

Exterior Orientation Parameters Exterior Orientation Parameters PERS 12/2001 pp 1321-1332 Karsten Jacobsen, Institute for Photogrammetry and GeoInformation, University of Hannover, Germany The georeference of any photogrammetric product

More information

Introduction to Mobile Robotics

Introduction to Mobile Robotics Introduction to Mobile Robotics Gaussian Processes Wolfram Burgard Cyrill Stachniss Giorgio Grisetti Maren Bennewitz Christian Plagemann SS08, University of Freiburg, Department for Computer Science Announcement

More information

Visual-Inertial Localization and Mapping for Robot Navigation

Visual-Inertial Localization and Mapping for Robot Navigation Visual-Inertial Localization and Mapping for Robot Navigation Dr. Guillermo Gallego Robotics & Perception Group University of Zurich Davide Scaramuzza University of Zurich - http://rpg.ifi.uzh.ch Mocular,

More information

Practical Course WS12/13 Introduction to Monte Carlo Localization

Practical Course WS12/13 Introduction to Monte Carlo Localization Practical Course WS12/13 Introduction to Monte Carlo Localization Cyrill Stachniss and Luciano Spinello 1 State Estimation Estimate the state of a system given observations and controls Goal: 2 Bayes Filter

More information

CAMERA POSE ESTIMATION OF RGB-D SENSORS USING PARTICLE FILTERING

CAMERA POSE ESTIMATION OF RGB-D SENSORS USING PARTICLE FILTERING CAMERA POSE ESTIMATION OF RGB-D SENSORS USING PARTICLE FILTERING By Michael Lowney Senior Thesis in Electrical Engineering University of Illinois at Urbana-Champaign Advisor: Professor Minh Do May 2015

More information

FAST REGISTRATION OF TERRESTRIAL LIDAR POINT CLOUD AND SEQUENCE IMAGES

FAST REGISTRATION OF TERRESTRIAL LIDAR POINT CLOUD AND SEQUENCE IMAGES FAST REGISTRATION OF TERRESTRIAL LIDAR POINT CLOUD AND SEQUENCE IMAGES Jie Shao a, Wuming Zhang a, Yaqiao Zhu b, Aojie Shen a a State Key Laboratory of Remote Sensing Science, Institute of Remote Sensing

More information

Estimation of Altitude and Vertical Velocity for Multirotor Aerial Vehicle using Kalman Filter

Estimation of Altitude and Vertical Velocity for Multirotor Aerial Vehicle using Kalman Filter Estimation of Altitude and Vertical Velocity for Multirotor Aerial Vehicle using Kalman Filter Przemys law G asior, Stanis law Gardecki, Jaros law Gośliński and Wojciech Giernacki Poznan University of

More information

Mapping Contoured Terrain Using SLAM with a Radio- Controlled Helicopter Platform. Project Proposal. Cognitive Robotics, Spring 2005

Mapping Contoured Terrain Using SLAM with a Radio- Controlled Helicopter Platform. Project Proposal. Cognitive Robotics, Spring 2005 Mapping Contoured Terrain Using SLAM with a Radio- Controlled Helicopter Platform Project Proposal Cognitive Robotics, Spring 2005 Kaijen Hsiao Henry de Plinval Jason Miller Introduction In the context

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

COS Lecture 13 Autonomous Robot Navigation

COS Lecture 13 Autonomous Robot Navigation COS 495 - Lecture 13 Autonomous Robot Navigation Instructor: Chris Clark Semester: Fall 2011 1 Figures courtesy of Siegwart & Nourbakhsh Control Structure Prior Knowledge Operator Commands Localization

More information

Autonomous navigation in industrial cluttered environments using embedded stereo-vision

Autonomous navigation in industrial cluttered environments using embedded stereo-vision Autonomous navigation in industrial cluttered environments using embedded stereo-vision Julien Marzat ONERA Palaiseau Aerial Robotics workshop, Paris, 8-9 March 2017 1 Copernic Lab (ONERA Palaiseau) Research

More information

DEVELOPMENT OF POSITION MEASUREMENT SYSTEM FOR CONSTRUCTION PILE USING LASER RANGE FINDER

DEVELOPMENT OF POSITION MEASUREMENT SYSTEM FOR CONSTRUCTION PILE USING LASER RANGE FINDER S17- DEVELOPMENT OF POSITION MEASUREMENT SYSTEM FOR CONSTRUCTION PILE USING LASER RANGE FINDER Fumihiro Inoue 1 *, Takeshi Sasaki, Xiangqi Huang 3, and Hideki Hashimoto 4 1 Technica Research Institute,

More information

Implementation of Odometry with EKF for Localization of Hector SLAM Method

Implementation of Odometry with EKF for Localization of Hector SLAM Method Implementation of Odometry with EKF for Localization of Hector SLAM Method Kao-Shing Hwang 1 Wei-Cheng Jiang 2 Zuo-Syuan Wang 3 Department of Electrical Engineering, National Sun Yat-sen University, Kaohsiung,

More information

Particle Filter in Brief. Robot Mapping. FastSLAM Feature-based SLAM with Particle Filters. Particle Representation. Particle Filter Algorithm

Particle Filter in Brief. Robot Mapping. FastSLAM Feature-based SLAM with Particle Filters. Particle Representation. Particle Filter Algorithm Robot Mapping FastSLAM Feature-based SLAM with Particle Filters Cyrill Stachniss Particle Filter in Brief! Non-parametric, recursive Bayes filter! Posterior is represented by a set of weighted samples!

More information

Overview of the Trimble TX5 Laser Scanner

Overview of the Trimble TX5 Laser Scanner Overview of the Trimble TX5 Laser Scanner Trimble TX5 Revolutionary and versatile scanning solution Compact / Lightweight Efficient Economical Ease of Use Small and Compact Smallest and most compact 3D

More information

Runway Centerline Deviation Estimation from Point Clouds using LiDAR imagery

Runway Centerline Deviation Estimation from Point Clouds using LiDAR imagery Runway Centerline Deviation Estimation from Point Clouds using LiDAR imagery Seth Young 1, Charles Toth 2, Zoltan Koppanyi 2 1 Department of Civil, Environmental and Geodetic Engineering The Ohio State

More information

Robot Mapping. A Short Introduction to the Bayes Filter and Related Models. Gian Diego Tipaldi, Wolfram Burgard

Robot Mapping. A Short Introduction to the Bayes Filter and Related Models. Gian Diego Tipaldi, Wolfram Burgard Robot Mapping A Short Introduction to the Bayes Filter and Related Models Gian Diego Tipaldi, Wolfram Burgard 1 State Estimation Estimate the state of a system given observations and controls Goal: 2 Recursive

More information

Zürich. Roland Siegwart Margarita Chli Martin Rufli Davide Scaramuzza. ETH Master Course: L Autonomous Mobile Robots Summary

Zürich. Roland Siegwart Margarita Chli Martin Rufli Davide Scaramuzza. ETH Master Course: L Autonomous Mobile Robots Summary Roland Siegwart Margarita Chli Martin Rufli Davide Scaramuzza ETH Master Course: 151-0854-00L Autonomous Mobile Robots Summary 2 Lecture Overview Mobile Robot Control Scheme knowledge, data base mission

More information

A Reactive Bearing Angle Only Obstacle Avoidance Technique for Unmanned Ground Vehicles

A Reactive Bearing Angle Only Obstacle Avoidance Technique for Unmanned Ground Vehicles Proceedings of the International Conference of Control, Dynamic Systems, and Robotics Ottawa, Ontario, Canada, May 15-16 2014 Paper No. 54 A Reactive Bearing Angle Only Obstacle Avoidance Technique for

More information

Anibal Ollero Professor and head of GRVC University of Seville (Spain)

Anibal Ollero Professor and head of GRVC University of Seville (Spain) Aerial Manipulation Anibal Ollero Professor and head of GRVC University of Seville (Spain) aollero@us.es Scientific Advisor of the Center for Advanced Aerospace Technologies (Seville, Spain) aollero@catec.aero

More information

Monocular Vision-based Displacement Measurement System Robust to Angle and Distance Using Homography

Monocular Vision-based Displacement Measurement System Robust to Angle and Distance Using Homography 6 th International Conference on Advances in Experimental Structural Engineering 11 th International Workshop on Advanced Smart Materials and Smart Structures Technology August 1-2, 2015, University of

More information

#65 MONITORING AND PREDICTING PEDESTRIAN BEHAVIOR AT TRAFFIC INTERSECTIONS

#65 MONITORING AND PREDICTING PEDESTRIAN BEHAVIOR AT TRAFFIC INTERSECTIONS #65 MONITORING AND PREDICTING PEDESTRIAN BEHAVIOR AT TRAFFIC INTERSECTIONS Final Research Report Luis E. Navarro-Serment, Ph.D. The Robotics Institute Carnegie Mellon University Disclaimer The contents

More information

Autonomous Indoor Hovering with a Quadrotor

Autonomous Indoor Hovering with a Quadrotor Autonomous Indoor Hovering with a Quadrotor G. Angeletti, J. R. Pereira Valente, L. Iocchi, D. Nardi Sapienza University of Rome, Dept. of Computer and System Science, Via Ariosto 25, 00185 Rome, Italy

More information

Advanced Robotics Path Planning & Navigation

Advanced Robotics Path Planning & Navigation Advanced Robotics Path Planning & Navigation 1 Agenda Motivation Basic Definitions Configuration Space Global Planning Local Planning Obstacle Avoidance ROS Navigation Stack 2 Literature Choset, Lynch,

More information

GPS denied Navigation Solutions

GPS denied Navigation Solutions GPS denied Navigation Solutions Krishnraj Singh Gaur and Mangal Kothari ksgaur@iitk.ac.in, mangal@iitk.ac.in https://www.iitk.ac.in/aero/mangal/ Intelligent Guidance and Control Laboratory Indian Institute

More information

Exam in DD2426 Robotics and Autonomous Systems

Exam in DD2426 Robotics and Autonomous Systems Exam in DD2426 Robotics and Autonomous Systems Lecturer: Patric Jensfelt KTH, March 16, 2010, 9-12 No aids are allowed on the exam, i.e. no notes, no books, no calculators, etc. You need a minimum of 20

More information

L10. PARTICLE FILTERING CONTINUED. NA568 Mobile Robotics: Methods & Algorithms

L10. PARTICLE FILTERING CONTINUED. NA568 Mobile Robotics: Methods & Algorithms L10. PARTICLE FILTERING CONTINUED NA568 Mobile Robotics: Methods & Algorithms Gaussian Filters The Kalman filter and its variants can only model (unimodal) Gaussian distributions Courtesy: K. Arras Motivation

More information

A novel approach to motion tracking with wearable sensors based on Probabilistic Graphical Models

A novel approach to motion tracking with wearable sensors based on Probabilistic Graphical Models A novel approach to motion tracking with wearable sensors based on Probabilistic Graphical Models Emanuele Ruffaldi Lorenzo Peppoloni Alessandro Filippeschi Carlo Alberto Avizzano 2014 IEEE International

More information

DEVELOPMENT OF A ROBUST IMAGE MOSAICKING METHOD FOR SMALL UNMANNED AERIAL VEHICLE

DEVELOPMENT OF A ROBUST IMAGE MOSAICKING METHOD FOR SMALL UNMANNED AERIAL VEHICLE DEVELOPMENT OF A ROBUST IMAGE MOSAICKING METHOD FOR SMALL UNMANNED AERIAL VEHICLE J. Kim and T. Kim* Dept. of Geoinformatic Engineering, Inha University, Incheon, Korea- jikim3124@inha.edu, tezid@inha.ac.kr

More information

ViconMAVLink: A SOFTWARE TOOL FOR INDOOR POSITIONING USING A MOTION CAPTURE SYSTEM

ViconMAVLink: A SOFTWARE TOOL FOR INDOOR POSITIONING USING A MOTION CAPTURE SYSTEM ViconMAVLink: A SOFTWARE TOOL FOR INDOOR POSITIONING USING A MOTION CAPTURE SYSTEM Bo Liu Coordinated Science Laboratory University of Illinois at Urbana-Champaign Urbana, IL 61801 boliu1@illinois.edu

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

Set up and Foundation of the Husky

Set up and Foundation of the Husky Set up and Foundation of the Husky Marisa Warner, Jeremy Gottlieb, Gabriel Elkaim Worcester Polytechnic Institute University of California, Santa Cruz Abstract Clearpath s Husky A200 is an unmanned ground

More information

Introduction to Autonomous Mobile Robots

Introduction to Autonomous Mobile Robots Introduction to Autonomous Mobile Robots second edition Roland Siegwart, Illah R. Nourbakhsh, and Davide Scaramuzza The MIT Press Cambridge, Massachusetts London, England Contents Acknowledgments xiii

More information

Probabilistic Robotics

Probabilistic Robotics Probabilistic Robotics FastSLAM Sebastian Thrun (abridged and adapted by Rodrigo Ventura in Oct-2008) The SLAM Problem SLAM stands for simultaneous localization and mapping The task of building a map while

More information

Non-symmetric membership function for Fuzzy-based visual servoing onboard a UAV

Non-symmetric membership function for Fuzzy-based visual servoing onboard a UAV 1 Non-symmetric membership function for Fuzzy-based visual servoing onboard a UAV M. A. Olivares-Méndez and P. Campoy and C. Martínez and I. F. Mondragón B. Computer Vision Group, DISAM, Universidad Politécnica

More information

Autonomous Navigation for Flying Robots

Autonomous Navigation for Flying Robots Computer Vision Group Prof. Daniel Cremers Autonomous Navigation for Flying Robots Lecture 3.2: Sensors Jürgen Sturm Technische Universität München Sensors IMUs (inertial measurement units) Accelerometers

More information

Localization and Map Building

Localization and Map Building Localization and Map Building Noise and aliasing; odometric position estimation To localize or not to localize Belief representation Map representation Probabilistic map-based localization Other examples

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

Camera Registration in a 3D City Model. Min Ding CS294-6 Final Presentation Dec 13, 2006

Camera Registration in a 3D City Model. Min Ding CS294-6 Final Presentation Dec 13, 2006 Camera Registration in a 3D City Model Min Ding CS294-6 Final Presentation Dec 13, 2006 Goal: Reconstruct 3D city model usable for virtual walk- and fly-throughs Virtual reality Urban planning Simulation

More information

Probabilistic Robotics. FastSLAM

Probabilistic Robotics. FastSLAM Probabilistic Robotics FastSLAM The SLAM Problem SLAM stands for simultaneous localization and mapping The task of building a map while estimating the pose of the robot relative to this map Why is SLAM

More information

James Van Rens CEO Riegl USA, Inc. Mining Industry and UAV s combined with LIDAR Commercial UAV Las Vegas October 2015 James Van Rens CEO Riegl USA

James Van Rens CEO Riegl USA, Inc. Mining Industry and UAV s combined with LIDAR Commercial UAV Las Vegas October 2015 James Van Rens CEO Riegl USA James Van Rens CEO Riegl USA, Inc. Mining Industry and UAV s combined with LIDAR Commercial UAV Las Vegas October 2015 James Van Rens CEO Riegl USA COST EFFECIENCY CONTINUUM LIDAR and IMU Partnership Technology

More information

CSE 527: Introduction to Computer Vision

CSE 527: Introduction to Computer Vision CSE 527: Introduction to Computer Vision Week 10 Class 2: Visual Odometry November 2nd, 2017 Today Visual Odometry Intro Algorithm SLAM Visual Odometry Input Output Images, Video Camera trajectory, motion

More information

Live Metric 3D Reconstruction on Mobile Phones ICCV 2013

Live Metric 3D Reconstruction on Mobile Phones ICCV 2013 Live Metric 3D Reconstruction on Mobile Phones ICCV 2013 Main Contents 1. Target & Related Work 2. Main Features of This System 3. System Overview & Workflow 4. Detail of This System 5. Experiments 6.

More information

AN INCREMENTAL SLAM ALGORITHM FOR INDOOR AUTONOMOUS NAVIGATION

AN INCREMENTAL SLAM ALGORITHM FOR INDOOR AUTONOMOUS NAVIGATION 20th IMEKO TC4 International Symposium and 18th International Workshop on ADC Modelling and Testing Research on Electric and Electronic Measurement for the Economic Upturn Benevento, Italy, September 15-17,

More information

Introduction to Mobile Robotics Techniques for 3D Mapping

Introduction to Mobile Robotics Techniques for 3D Mapping Introduction to Mobile Robotics Techniques for 3D Mapping Wolfram Burgard, Michael Ruhnke, Bastian Steder 1 Why 3D Representations Robots live in the 3D world. 2D maps have been applied successfully for

More information

3D-2D Laser Range Finder calibration using a conic based geometry shape

3D-2D Laser Range Finder calibration using a conic based geometry shape 3D-2D Laser Range Finder calibration using a conic based geometry shape Miguel Almeida 1, Paulo Dias 1, Miguel Oliveira 2, Vítor Santos 2 1 Dept. of Electronics, Telecom. and Informatics, IEETA, University

More information

Construction Progress Management and Interior Work Analysis Using Kinect 3D Image Sensors

Construction Progress Management and Interior Work Analysis Using Kinect 3D Image Sensors 33 rd International Symposium on Automation and Robotics in Construction (ISARC 2016) Construction Progress Management and Interior Work Analysis Using Kinect 3D Image Sensors Kosei Ishida 1 1 School of

More information

REGISTRATION OF AIRBORNE LASER DATA TO SURFACES GENERATED BY PHOTOGRAMMETRIC MEANS. Y. Postolov, A. Krupnik, K. McIntosh

REGISTRATION OF AIRBORNE LASER DATA TO SURFACES GENERATED BY PHOTOGRAMMETRIC MEANS. Y. Postolov, A. Krupnik, K. McIntosh REGISTRATION OF AIRBORNE LASER DATA TO SURFACES GENERATED BY PHOTOGRAMMETRIC MEANS Y. Postolov, A. Krupnik, K. McIntosh Department of Civil Engineering, Technion Israel Institute of Technology, Haifa,

More information

Using constraint propagation for cooperative UAV localization from vision and ranging

Using constraint propagation for cooperative UAV localization from vision and ranging Using constraint propagation for cooperative UAV localization from vision and ranging Ide-Flore Kenmogne, Vincent Drevelle, and Eric Marchand Univ Rennes, Inria, CNRS, IRISA ide-flore.kenmogne@inria.fr,

More information

Decentralized Control of a Quadrotor Aircraft Fleet to seek Information

Decentralized Control of a Quadrotor Aircraft Fleet to seek Information Decentralized Control of a Quadrotor Aircraft Fleet to seek Information Claire J. Tomlin, Gabe Hoffmann, Maryam Kamgarpour, Robin Raffard, and Steven Waslander Electrical Engineering and Computer Sciences

More information

IEEE/CAA JOURNAL OF AUTOMATICA SINICA, VOL. 2, NO. 1, JANUARY Robust and Accurate Monocular Visual Navigation Combining IMU for a Quadrotor

IEEE/CAA JOURNAL OF AUTOMATICA SINICA, VOL. 2, NO. 1, JANUARY Robust and Accurate Monocular Visual Navigation Combining IMU for a Quadrotor IEEE/CAA JOURNAL OF AUTOMATICA SINICA, VOL. 2, NO. 1, JANUARY 2015 33 Robust and Accurate Monocular Visual Navigation Combining IMU for a Quadrotor Wei Zheng, Fan Zhou, and Zengfu Wang Abstract In this

More information

UAV Position and Attitude Sensoring in Indoor Environment Using Cameras

UAV Position and Attitude Sensoring in Indoor Environment Using Cameras UAV Position and Attitude Sensoring in Indoor Environment Using Cameras 1 Peng Xu Abstract There are great advantages of indoor experiment for UAVs. Test flights of UAV in laboratory is more convenient,

More information

Chapters 1 9: Overview

Chapters 1 9: Overview Chapters 1 9: Overview Chapter 1: Introduction Chapters 2 4: Data acquisition Chapters 5 9: Data manipulation Chapter 5: Vertical imagery Chapter 6: Image coordinate measurements and refinements Chapters

More information

ENY-C2005 Geoinformation in Environmental Modeling Lecture 4b: Laser scanning

ENY-C2005 Geoinformation in Environmental Modeling Lecture 4b: Laser scanning 1 ENY-C2005 Geoinformation in Environmental Modeling Lecture 4b: Laser scanning Petri Rönnholm Aalto University 2 Learning objectives To recognize applications of laser scanning To understand principles

More information

INSPIRE 1 Quick Start Guide V1.0

INSPIRE 1 Quick Start Guide V1.0 INSPIRE Quick Start Guide V.0 The Inspire is a professional aerial filmmaking and photography platform that is ready to fly right out of the box. Featuring an onboard camera equipped with a 0mm lens and

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

User-Guided Dimensional Analysis of Indoor Scenes Using Depth Sensors

User-Guided Dimensional Analysis of Indoor Scenes Using Depth Sensors User-Guided Dimensional Analysis of Indoor Scenes Using Depth Sensors Yong Xiao a, Chen Feng a, Yuichi Taguchi b, and Vineet R. Kamat a a Department of Civil and Environmental Engineering, University of

More information

3D object recognition used by team robotto

3D object recognition used by team robotto 3D object recognition used by team robotto Workshop Juliane Hoebel February 1, 2016 Faculty of Computer Science, Otto-von-Guericke University Magdeburg Content 1. Introduction 2. Depth sensor 3. 3D object

More information

Monte Carlo Localization using Dynamically Expanding Occupancy Grids. Karan M. Gupta

Monte Carlo Localization using Dynamically Expanding Occupancy Grids. Karan M. Gupta 1 Monte Carlo Localization using Dynamically Expanding Occupancy Grids Karan M. Gupta Agenda Introduction Occupancy Grids Sonar Sensor Model Dynamically Expanding Occupancy Grids Monte Carlo Localization

More information

Technical Paper of HITCSC Team for The International Aerial Robotics Competition

Technical Paper of HITCSC Team for The International Aerial Robotics Competition Technical Paper of HITCSC Team for The International Aerial Robotics Competition Qingtao Yu, Yuanhong Li, Hang Yu, Haodi Yao, Rui Xing, Qi Zhao, Xiaowei Xing Harbin Institute of Tecnology ABSTRACT This

More information

Particle Filters. CSE-571 Probabilistic Robotics. Dependencies. Particle Filter Algorithm. Fast-SLAM Mapping

Particle Filters. CSE-571 Probabilistic Robotics. Dependencies. Particle Filter Algorithm. Fast-SLAM Mapping CSE-571 Probabilistic Robotics Fast-SLAM Mapping Particle Filters Represent belief by random samples Estimation of non-gaussian, nonlinear processes Sampling Importance Resampling (SIR) principle Draw

More information

Monocular SLAM for a Small-Size Humanoid Robot

Monocular SLAM for a Small-Size Humanoid Robot Tamkang Journal of Science and Engineering, Vol. 14, No. 2, pp. 123 129 (2011) 123 Monocular SLAM for a Small-Size Humanoid Robot Yin-Tien Wang*, Duen-Yan Hung and Sheng-Hsien Cheng Department of Mechanical

More information