Wednesday, June 29th


The goal of the RoboCup initiative is that 
“By the mid-21st century, a team of fully autonomous humanoid 
soccer players shall win the soccer game, comply with the official 
rule of the FIFA, against the winner of the most recent World Cup”. 
As the IAV 2016 is co-located with the 20th RoboCup, it is time 
to review what has been achieved in the area of humanoid robots 
that autonomously play soccer in teams.

Dr. Thomas Röfer, German Research Center for Artificial Intelligence, Cyber-Physical Systems


This paper describes the development of an optimized path
planning algorithm for automated vehicles in urban
environments. This path planning is developed on the basis
of urban environments, where Cybernetic Transportation
Systems (CTS) will operate. Our approach is mainly affected
by vehicle's kinematics and physical road constraints. 
Based on this assumptions, computational time for path
planning can be significantly reduced by creating an
off-line database that already optimized all the potential
trajectories in each curve the CTS can carry out.
Therefore, this algorithm generates a database of smooth
and continuous curves considering a big set of different
intersection scenarios, taking into account the constraints
of the infrastructure and the physical limitations of the
vehicle. According to the real scenario, the local planner
selects from the database the appropriate curves from
searching for the ones that fit with the intersections
defined on it. The path planning algorithm has been tested
in simulation using the previous control architecture. The
results obtained show path generation improvements in terms
of smoothness and continuity. Finally, the proposed
algorithm was compared with previous path planning
algorithms for its assessment.

Fernando José Garrido Carpio1,2, David Enrique González Bautista1, Vicente Milanés1, Joshue M Perez Rastelli1, Fawzi Nashashibi1
1Robotics and Intelligent Transportation Systems (RITS) Team, Inria, France, 2Vedecom institute, France

Thanks to the continuously increasing computational power
of CPUs, nowadays Model Predictive Control (MPC), initially
designed for multi-variable control of chemical plants, is
adopted in a large number of different applications,
covering a wide range of process dynamics ranging from slow
to even fast time scales. As a consequence, a renewed
interest in numerical optimization tools, especially for
nonlinear systems, arose. This work aims at demonstrating
the feasibility of a novel methodology, based on a Linear
Fractional Transform (LFT) formulation of the system
dynamics, that allows to efficiently solve nonlinear MPC
problems. An application example, concerning the tracking
control of an autonomous vehicle, shows the effectiveness
of the proposal.

Luca Bascetta, Gianni Ferretti, Marco Bossi
Politecnico di Milano, Dipartimento di Elettronica, Informazione e Bioingegneria, Italy

In the last few years the number of applications of
autonomous mobile robots to outdoor and off-road tasks,
like border surveillance and monitoring, search and rescue,
agriculture, driveless mobility has been rapidly
increasing. Among the huge number of functionalities that
are required to make a vehicle an autonomous robot,
localisation, path planning and trajectory tracking are the
most important. This paper proposes a novel approach to
solve the trajectory tracking problem of an Ackermann
steering vehicle. A multi-body dynamic model of the vehicle
is proposed as a mean to tune and validate the tracking
controller. The proposal is supported by an experimental
validation, that shows the effectiveness of the trajectory
tracking controller and its performance in comparison with
the accuracy of the localisation algorithm.

Luca Bascetta1, Davide Antonio Cucci2, Matteo Matteucci1
1Politecnico di Milano, Dipartimento di Elettronica, Informazione e Bioingegneria, Italy, 2École Polytechnique Fédérale de Lausanne, Geodetic Engineering Laboratory, Switzerland

This paper presents a nonlinear path tracking controller
for autonomous bi-steerable (four-wheel steering or 4WS)
vehicles, allowing high precision tracking even when the
reference path proposes fast varying curvature. Indeed,
such paths are very common as soon as vehicles have to
avoid obstacles in cluttered environments. Considering the
well-known bicycle model, the sole reference path usually
defined for the rear wheel is replaced by two synchronized
paths, introducing a new way to calculate the expected yaw
rate of the vehicle without numerical derivatives.
Equations describing the motion of the vehicle with respect
to this dual-path are presented and used to design the
proposed control law. Then, simulations and experiments
with the electrical public transport vehicle EZ10
demonstrate the controller ability to precisely follow
complex trajectories.

Ange Nizard1,2, Benoit Thuilot1,2, Roland Lenain3, Youcef Mezouar1,4
1CNRS, UMR 6602, Institut Pascal, France, 2Clermont Université, Université Blaise Pascal, Institut Pascal, France, 3Irstea, France, 4Clermont Université, IFMA, Institut Pascal, France

In this work we address simultaneous pose tracking and
sensor parameter self-calibration by applying the
pose-graph optimization approach. A factor-graph is
employed to store robot pose estimates at different time
instants and calibration parameters such as magnetometer
hard and soft iron distortion and gyroscope bias. Specific
factors are developed in this paper to handle Ackermann
kinematic readings, inertial measurement units,
magnetometers and global positioning systems in the
pose-based factor-graph. An experimental evaluation
supports the viability of the approach considering an
autonomous all-terrain vehicle, for which we perform
calibration and real-time pose tracking during navigation.

Davide Antonio Cucci1, Matteo Matteucci2, Luca Bascetta2
1École Polytechnique Fédérale de Lausanne, Geodetic Engineering Laboratory, Switzerland, 2Politecnico di Milano, Dipartimento di Elettronica, Informazione e Bioingegneria, Italy

An energy efficient local path planner for navigation of
omnidirectional battery-powered mobile robots in dynamic
environments. The proposed algorithm extends the Dynamic
Window Approach (DWA) to incorporate a cost function based
on energy consumption. The estimated energy consumption
during planning is predicted using a linear regression
model that is learned on the fly using a variable learning
rate. Empirical results are presented on a mobile robot
platform that show a 9.79\% decrease in energy consumption
in comparison to the DWA approach.

Christian Henkel1, Alexander Bubeck1, Weiliang Xu2
1Fraunhofer Institute for Manufacturing Engineering and Automation IPA, Germany, 2Department of Mechanical Engineering, University of Auckland, New Zealand



Inaccurate actuator responses affect the behavior of an
autonomous driving system. A disadvantageous combination of
such inaccuracies might lead to a collision, but is hard to
test in advance due to the exponentially large number of
possible combinations. This paper introduces STARVEC, a
tool to test autonomous driving systems for undesired
behaviors in the presence of sensor and actuator
inaccuracies in a simulation environment. It stores
intermediate states of the simulation and uses these states
to efficiently explore the space of possible behaviors.
Each step continues with the execution of the state with
the highest distance to its neighbors. Thus, the
potentially large space of reachable states is covered fast
and increasingly dense. The approach is applied to an
autonomous parking system with inaccurate actuators and its
performance is compared to a Monte-Carlo algorithm and a
previous prototype.

Pascal Minnerup1, Alois Knoll2
1fortiss, An-Institut der Technischen Universität München, Germany, 2Robotics and Embedded Systems, Universität München, Germany

In the development of software-intensive systems in a
vehicle, like an autonomous driving system, defects are
often only recognized during trials on the physical
vehicle. In contrast to a simulation environment, a
physically executed maneuver does not offer the possibility
to pause and debug critical code sections or to reproduce
and repeat faulty trials. Furthermore, development space
and capacities are limited inside the car. Therefore, it is
best practice to analyze faults observed during a physical
execution offline and to reproduce faulty trials in a
simulation environment. The repetition in a simulation
environment is a time consuming effort but necessary for
pushing the software component towards a state in which it
showed the faulty behavior. This paper shows an approach
for executing the faulty state again in a simulation
environment by serializing the exact state of the software
system and summarizes practical experience gained by this
approach.

Pascal Minnerup1, David Lenz1, Tobias Kessler1, Alois Knoll2
1fortiss, An-Institut der Technischen Universität München, Germany, 2Robotics and Embedded Systems, Universität München, Germany

The work presented in this paper focuses on the comparison
of well-known and new
techniques for designing robust fault diagnosis schemes in
the robot domain. Correctly identifying and
handling faults is an inherent characteristic that all
autonomous mobile agents should possess, as none
of the hardware and software parts used by robots are
perfect; instead, they are often error-prone and
able to introduce serious problems that might endanger both
robots and their environment.
Based on a study of literature covering model-based
fault-diagnosis algorithms, we selected four of
these methods based on both linear and non-linear models.
We analyzed and implemented them in a
mathematical model, representing a four-wheel-OMNI mobile
robot. Numerical examples were used to
test the ability of the algorithms to detect and identify
abnormal behavior and to optimise the model
parameters for the given training data.
The final goal was to point out the strengths of each
algorithm and to figure out which method would
best suit the demands of fault diagnosis for a particular
mobile robot.

Anastassia Kuestenmacher, Paul G. Plöger
Bonn-Rhein-Sieg University of Applied Sciences, Germany

The verification of safety is expected to be one of the
largest challenges in the commercialization of autonomous
vehicles. Using traditional methods would require
infeasible time and resources. Recent research has shown
the possibility of using near-collisions in order to
estimate the frequency of actual collisions using Extreme
Value Theory. However, little research has been done on how
the measure for determining the closeness to a collision
affect the result of the estimation. This paper compares a
time-based measure against one that relates to an
inevitable collision state. The result shows that the
latter one is the more robust choice and that more research
needs to be made into measure of collision proximity.

Daniel Åsljung1,2, Jonas Nilsson1, Jonas Fredriksson2
1Department of Active Safety, Volvo Car Corporation, Sweden, 2Department of Signals and Systems, Chalmers University of Technology, Sweden

In this paper we studied a system fault detection and
isolation in a networked Multi-UAVs formation flight set-up
using a Cubature Kalman Filter (CKF). Both actuator and
sensor faults of a UAV are considered as an agent node
fault on the system of UAVs in the formation flight. The
CKF based fault detection scheme developed is used in order
to detect a system wide fault in the formation flight.
Furthermore, the graph theoretic approach used for modeling
the multi agent UAV's communication is exploited to isolate
the faulty UAV (node) from the flight formation. A numerical
simulation is presented to confirm the proposed fault 
detection and isolation (FDI) performance.

Sang-Hyeon Kim, Han-Lim Choi, Lebsework Negash Lemma
Korean Advanced Institute of Science and Technology, Daejeon, Korea




The development of precise and robust navigation strategies
for Autonomous Underwater Vehicles (AUVs) is fundamental
to reach the high level of performance required by
complex underwater tasks, often including more than one
AUV. One of the main factors affecting the accuracy of AUVs 
navigation systems is the algorithm used to estimate the 
vehicle motion, usually based on kinematic vehicle models and 
linear estimators. In this paper, the authors present 
a navigation strategy specifically designed for AUVs, based 
on the Unscented Kalman Filter (UKF). The algorithm proves 
to be effective if applied to this class of vehicles and allows
to achieve a satisfying accuracy improvement compared to
standard navigation algorithms. The proposed strategy has been 
experimentally validated in suitable sea tests performed near
the Cala Minnola wreck (Levanzo, Aegadian Islands, Sicily,
Italy). The vehicles involved are the Typhoon AUVs, 
developed and built by the Department of Industrial Engineering 
of the University of Florence during the THESAURUS Tuscany Region
project and the European ARROWS project for exploration 
and surveillance of underwater archaeological sites. The
proposed algorithm has been implemented online on the AUVs
and tested. The validation of the proposed strategy provided 
accurate results in estimating the vehicle dynamic behavior, 
better than those obtained through standard navigation algorithms.

Benedetto Allotta1, Andrea Caiti2, Riccardo Costanzi1, Francesco Fanelli1, Enrico Meli1, Alessandro Ridolfi1
1Department of Industrial Engineering (DIEF), Mechatronics and Dynamic Modelling Laboratory (MDM Lab), University of Florence (UNIFI), Italy 2Centro Piaggio, University of PISA (UNIPI), Italy

Strategies of AUV navigation for achieving the near-bottom
survey of a steep terrain are addressed. Unlike a flat
terrain, a steep terrain can disrupt an altitude-based
bottom-following dive of a cruising AUV. During its
near-bottom dive over a steep terrain, a cruising AUV
possibly experience longitudinal motion instability
accompanied by severely fluctuating heave and pitch which
may lead to bottom collision of the vehicle. Based on dive
simulations, it is shown that the lost bottom lock of a
sonar altimeter and the altitude overestimation are two
major sources of the longitudinal motion instability.
Underwater acoustic physics interacting with the sea water
and bottom, as well as the coupled 3-d.o.f. longitudinal
vehicle dynamics are incorporated into our simulation
model. As alternative strategies for pursuing more reliable
AUV-based near-bottom survey, the slope-following
navigation and the pseudo bottom-following navigation have
been investigated.

Kangsoo Kim1, Tamaki Ura2
1National Maritime Research Institute, Japan, 2Kyushu Institute of Technology, Japan

The paper addresses the computation of the information
theoretic inspired empowerment quantity for a simplified
vertical plane dynamic model of a Folaga autonomous
underwater vehicle. Online empowerment computation can be
exploited within complex autonomous robotics missions. In
fact empowerment can be used to measure how much influence
a vehicle has on its environment, and it identifies
desirable states of the vehicle, hence it can act as an
intrinsic cost function to use during a mission. In
particular, the proposed approach is being developed in the
framework of and H2020 underwater robotics research project
(Widely scalable Mobile Underwater Sonar Technology)
addressing the use of autonomous underwater vehicles for
acoustic seismic applications.

Nicola Catenac1i Volpi1, Daniela De Palma2, Daniel Polani1, Giovanni Indiveri2
1Department of Computer Science, University of Hertfordshire, United Kingdom, 2Dipartimento Ingegneria Innovazione, University of Salento - ISME, Italy

This paper presents the initial stage of the development of
an underwater localization system suitable for a flexible
number of users. Multiple AUVs can work as a team and
cooperate with other teams of AUVs without costly and even
acoustically active components, which saves energy and
allows AUVs to remain silent. The main building blocks for
such a system are: spiral wavefront beacon in conjunction
with a standard (circular) acoustic modem, Chip Scale
Atomic Clocks (CSAC), acoustic modems, state-of-the-art
adaptive underwater networking and Cooperative Localization
(CL) algorithms. Using the difference in time of arrival
between the spiral wavefront and the modem circular
wavefront, receivers will be able to determine the bearing
to the source using only one hydrophone. Synchronizing
vehicles Chip Scale Atomic Clocks (CSAC) with the beacon at
the beginning of the mission and during the longer missions
will ensure the vehicles ability to also calculate their
distance from the beacon upon every message reception.

Vladimir Djapic1, Wenjie Dong2, Petrika Gjanci3, Chiara Petrioli3, Daniele Spaccini3, Gianni Cario4, Alessandro Casavola4, Marco Lupia4
1SPAWAR Systems Center Pacific, USA, 2Department of Electrical Engineering, the University of Texas, USA, 3Computer Science Department, University of Rome, “La Sapienza,” Italy and WSENSE s.r.l., Rome, Italy, 4Department of Informatics, Modelling, Electronics and Systems, University of Calabria, Rende, Italy and Applicon s.r.l., Rende, Italy



Thursday, June 30th

This paper presents an autonomous navigation architecture
for a robot using stereo vision-based localisation. The
main contribution is the prediction of the quality of
future localisation of the system in order to detect and
avoid areas where vision-based localisation may fail, due
to lack of texture in the scene. A criterion based on the
estimation of future visible landmarks, considering
uncertainties on landmarks and camera positions, is
integrated in a Model Predictive Control loop to compute
safe trajectories with respect to the visual localisation.
The system was tested on a mobile robot and the obtained
results demonstrate the effectiveness of our method.

Hélène Roggeman, Julien Marzat, Anthelme Bernard-Brunel, Guy Le Besnerais
ONERA – The French Aerospace Lab, France

Robust text detection and recognition on an arbitrarily
distributed, unrestricted image areas is a difficult
problem, e.g. when interpreting traffic panels outdoors
during autonomous driving. Most previous work in Text
detection only considers single script, usually Latin, and
it is not able to detect text with multiple scripts.
This contribution combines an established technique
-Maximum Stable Extremal Regions- with a histogram of
stroke width feature (HSW) and a Support Vector Machine
classifier. We combined characters into groups by ray
casting and merge aligned groups into lines of text that
can also be verified by using the HSW. We evaluated our
detection pipeline on our own dataset of Autobahn road
scenes, and show how the character classifier stage can be
trained with one script and be successfully tested on a
different one. While precision and recall at least match to
state of the art solution, a unique characteristic of the
HSW feature is that it can learn and detect multiple
scripts, which yields true script independence.

Matias Alejandro Valdenegro Toro1, Paul Plöger1, Stefan Eickeler2, Iuliu Konya2
1Hochschule Bonn-Rhein-Sieg, Germany, 2Fraunhofer IAIS, Germany

In this work we present a method for visual odometry that
allows robust 3DoF
trajectory estimation for wheeled robots using a downward
facing RGBD-camera. Assuming
that the robot moves on a ground plane while the
environment itself can have arbitrary geometry
allows us to estimate the frame to frame motion from
orthographic projections of the RGBD-
data. Instead of directly aligning these projections, the
reference frame is split into blocks, which
are individually registered using ESM, and thus create
several estimates of the current motion.
These estimates are combined using an outlier rejection
scheme to create a robust estimate of
the actual motion even under challenging conditions. We
compare the results of our method to
results of several state-of-the-art methods to show its
accuracy and robustness.

Julian Jordan, Andreas Zell
Department of Computer Science, Faculty of Science, University of Tuebingen, Germany

In this paper, we present a system for autonomous object
search and exploration in cluttered environments. The
system shortens the average time needed to complete search
tasks by continually planning multiple perception actions
ahead of time using probabilistic prior knowledge. Useful
sensing actions are found using a frontier-based view
sampling technique in a continuously built 3D map. We
demonstrate the system on real hardware, investigate the
planner’s performance in three experiments in simulation,
and show that our approach achieves shorter overall run
times of search tasks compared to a greedy strategy.

Thorsten Gedicke, Martin Günther, Joachim Hertzberg
University of Osnabrück, Germany

This work proposes a full pipeline for a robot to
autonomously explore, model and segment an apartment.
Viewpoints are found offline and then visited by the robot
to create a 3-D model of the environment. This model is
segmented in order to find the various rooms and how they
are linked (windows, doors, walls) yielding a topological
map. Moreover areas of interest are also segmented, in this
case furniture's planar surfaces. The method is validated
on a realistic three rooms apartment. Results show that,
despite occlusion, autonomous exploration and modelling
covers 95\% of the appartment. For the segmentation part, 1
link out of 14 is wrongly classified while all the existing
areas of interest are found.

Guido Manfredi1, Sandra Devin1, Michel Devy1, Daniel Sidobre2
1AAS-CNRS, France, 2LAAS, UPS, Universite de Toulouse, France

In this paper we present an extension of Large Scale Kinect
Fusion to compute optimized triangle meshes on-the-fly by
removing redundant triangles on planar surfaces. The
optimization is integrated into the reconstruction pipeline
to compute the optimized meshes asynchronously to the
reconstruction process in real time. The computed
reconstructions can be extracted directly without the need
of any post processing.

Tristan Igelbrink1, Thomas Wiemann1, Joachim Hertzberg2
1Knowledge Based Systems Group, Osnabrück University, Germany, 2Knowledge Based Systems Group and DFKI Robotics Innovation Center Osnabrück, Germany



For about 80 years, people have been dreaming of cars that are able to drive by themselves.
These days, this vision is starting to become reality. For the first time, cars found their way
over a long distance in the Darpa Grand Challenge in 2005. Two years later, the famous
Darpa Urban Challenge took place. In both events, all finalists based their systems on active
sensors, and Google also started their impressive work with a high-end laser scanner
accompanied by radars. 

In 2013, we let a new S-class vehicle with close to production cameras und radars drive itself
from Mannheim to Pforzheim, following the route that Bertha Benz took 125 years ago.
Many lessons have been learned from that experiment; above all that (computer) vision will
become a key to autonomous driving, because we need a deep understanding of the scene if
we want cars to drive safely in complex urban traffic. This can only be obtained through
vision.

In my talk, I will first summarize Bertha’s drive and the lessons that we learned from it. In the
second part, I will present recent work towards achieving the necessary scene
understanding. Based on modern CNNs, we are able to assign object labels to each pixel and
to derive a rich but compact representation of the scene that serves as the basis of our work
on autonomous cars. Within just a few years these new approaches radically changed the
way we look at image understanding – more a revolution than an evolution.

Dr. Uwe Franke, Daimler Research and Development



Besides longitudinal control, advanced driving assistance
functions additionally require lateral control.
Up to now many different control approaches have been
proposed and documented in literature dealing with lateral
control. In contrast to this, there are only very few
publications describing the handling of comfortable
handover from manual to assisted driving controlling
lateral car dynamics. The presented work aims to enhance
handover at the activation of lateral control by
significantly reducing lateral acceleration and jerk,
resulting in smooth and comfortable control handover. First
a state of the art model-based control is outlined. Based
on this application a flatness-based approach for bumpless
transfer from manual to controlled mode is proposed. Both,
model-based control and bumpless transfer extension, allow
straight forward tuning and execution on standard
automotive hardware, due their low computational effort.
Results are discussed on simulation results.

Georg Nestlinger, Michael Stolz
Virtual Vehicle Research Center, Austria

The knowledge of tire-ground interaction forces is
interesting for intelligent vehicles. However, tire forces
transducers are expensive and not suitable for ordinary
passengers cars. An alternative is to estimate these forces
using common sensors. This paper presents an estimator
structure capable of reconstruct tire-ground interaction
forces in all directions. A delayed interconnected
cascade-observer structure is proposed to eliminate mutual
dependence between estimators. Observers are developed
based on nonlinear vehicle dynamic models with the Extended
Kalman Filter algorithm. The estimator is validated with
experimental results. The results are also compared with an
existent estimator of the literature. 

Rafael de Angelis Cordeiro1, Alessandro Victorino2, Paulo A Valente Ferreira1, Ely Paiva3, Samuel Siqueira Bueno4
1School of Electrical and Computer Engineering, University of Campinas, Brazil, 2Heudiasyc Lab, Université de Technologie de Compiègne, Compiègne, France, 3School of Mechanical Engineering, University of Campinas, Brazil, 4Division of Robotics and Computer Vision, Center for Information Technology Renato Archer, Campinas, Brazil

The availability of an efficient and reliable path planning
strategy is a great benefit
to mobile robots. Being able to intelligently connect a
series of waypoints is a crucial requirement
for the execution of autonomous navigation tasks. Several
performance indices can be used to
evaluate the goodness of a path, including its length and
smoothness. In this paper, the authors
focus on planar path planning for mobile robots; Bézier
curves are employed, optimizing the
computed path with respect to length and curvature, the
latter used as a measure of smoothness.
Due to the complexity of the objective function,
optimization is performed by means of a direct
search method. The proposed approach aims at generating
paths offering advantages to mobile
robots navigation in terms of controllability and reducing
the related power consumption. The
performed tests show that the presented method allows to
achieve interesting results, suggesting
its viability as a suitable path planning strategy for
different kinds of mobile robots.

Riccardo Costanzi, Francesco Fanelli, Enrico Meli, Alessandro Ridolfi, Benedetto Allotta
Department of Industrial Engineering (DIEF), Mechatronics and Dynamic Modelling Laboratory (MDM Lab), University of Florence, Italy

This paper documents the study on car-following behaviors
under different environmental conditions and with different
leading vehicle types on freeway. Unlike previous studies,
in which filed data were collected at limited segments or
simulation data were used, car-following time series
covering large amount of freeway scenarios were extracted
from the up-to-date Strategic Highway Research Program
(SHRP2) Naturalistic Driving Study database. Differences
and distributions of following headway and kinetic patterns
were compared for different following conditions. New
findings were concluded and compared with previous studies.
The results can be used as references for microscopic
traffic modeling and intelligent transportation systems.

Xinli Geng1,2,3, Huawei Liang2, Hao Xu3, Biao Yu2
1Department of Automation, University of Science and Technology of China, Hefei, China, 2Institute of Applied Technology, Hefei Institutes of Physical Science, Chinese Academy of Sciences, Hefei, China, 3Department of Civil and Environmental Engineering, University of Nevada, USA

Recent advances in autonomous driving and vehicle
connectivity help to ensure safety and comfort in various
driving conditions. These trends have widenened the system
boundary conditions for hybrid powertrain operation with
driving trajectory planning hence offering potential to
improve powertrain operational efficiency. This paper
presents an energy management (EM) controller for a plug-in
hybrid vehicle exploiting predicted velocity trajectory
together with its integration in both autonomous
longitudinal guidance and driver-aware scenarios. The
driver-aware scenario uses markov chain based stochastic
modelling of driving characteristics. The proposed EM
controller solves online, a discretized version of the fuel
consumption minimization problem using direct methods
transcribing the problem into a finite dimensional mixed
boolean quadratic problem with polytopic constraints.
Convex part of the resulting problem is solved using an
active set method. Simulation results from different
driving situations based on standard driving cycle and real
world driving scenarios demonstrate the functionality of
the controller and its flexbility to handle varying control
objectives.

Raja Sangili Vadamalu, Christian Beidl
Institute for Internal Combustion Engines and Powertrain Systems, Darmstadt University of Technology, Germany



The article presents a tool which assesses the risk of
automotive accidents taking into account the interactions
between environment, driver and vehicle. The evaluated risk
is composed of two parts: one concerns the impending risk
(i.e. risk of a clearly identified danger and which is
present in a short time horizon) and the other one, the
latent risk (i.e. risky behavior of the driver which can
lead to an accident). The developed tool uses information
present in the CAN bus, additional sensors and car
communication for shared sensing. With the collected
information and estimated variables (e.g. grip and reaction
time), it infers a probability of risk with a Bayesian
Network. The tool can also be used for evaluating
autonomous car driving and driver decisions.

Jean-Nicola Russo, Thomas Sproesser, Frédéric Drouhin, Michel Basset
Modelisation Intelligence Process Systems, Haute-Alsace University, France

This contribution proposes an application of an
optimisation algorithm to be implemented in an intelligent
drive assistant.  A vehicle dynamic model is introduced and
after the characterisation of its considered nonlinearities
some elements of the background concerning "Dynamic
Programming" are given together with the proposed
algorithm. A two-point boundary value optimization problem
in term of velocity is proposed with its solution using the
well-known "Dynamic Programming" method. Because of the
nonlinearity of the considered problem, using numerical
methods seems to be the only way solving it.  Using
"Dynamic programming" such kind of a complex problem is
solved by dividing it  into a collection of simpler
subproblems. At the end, an optimal feedback controller for
the angular position of the throttle valve of the engine is
proposed. Simulation results are discussed together with
possible application aspects such as "Curse of
Dimensionality" and an explicit analysis concerning the
calculation effort.

Simon Schmidt, Paolo Mercorelli
Institute of Product and Process Innovation, Leuphana University of Lueneburg, Germany

This paper presents a compact and fast data association
which can be used in tracking-by-detection based multiple
pedestrian tracking approaches. The goal is to make the
data association simple and robust so that it can be really
useful in compact computing environment. This is realized
by replacing computationally heavy Bayesian based filter
with the compact Median Flow tracker. Two layers of data
association are proposed for fulfilling different
requirements of tracking tasks. Afterwards, we assess the
performance of the algorithm by evaluating it on a standard
dataset. Experimental results show that it improves the
processing speed upon state-of-art methods tremendously
with only trading off limited performance.

Songlin Piao, Tanittha Sutjaritvorakul, Karsten Berns
Computer Science Department, University of Kaiserslautern, Germany

In order to improve the longitudinal control behavior of
automated vehicles, a predictive control scheme with an
adaptive vehicle state and parameter observer is proposed.
The underlying nonlinear model of vehicle and powertrain
dynamics makes use of the estimated torque signal which is
calculated in the engine management system, as well as of
vehicle speed and acceleration measurements. An Extended
Kalman Filter is implemented to both estimate filtered
vehicle states and the vehicle mass.
Simulation results show good convergence of the parameter
estimate.
The contributions of this paper build the foundation to
further examine the potential of improvement in fuel
savings, planning accuracy and passenger comfort.

Martin Buechel1, Alois Knoll2
1fortiss GmbH, Munich, Germany, 2Technical University of Munich (TUM), Robotics and Embedded Systems, Germany

Collision avoidance systems demand sophisticated control
algorithms to ensure driving on a safe
preplanned path. Model predictive control (MPC) is suitable
for this task as different influences
can be considered by the algorithm. However MPC requires a
model of the plant to guarantee
good control characteristics. Especially the task to
generate a simple steering model covering
the considered range of vehicle dynamics is challenging. In
this work a concept for an adaptive
steering model is presented. The adaptive steering model is
integrated in a model predictive
control concept for collision avoidance maneuvers.
Simulation results show the effectiveness for
different maneuvers.

Boliang Yi, Jens Ferdinand, Norbert Simm, Frank Bonarens
Adam Opel AG, Germany

A nonlinear model predictive control (NMPC) approach for
steering an autonomous mobile robot is presented. The
vehicle dynamics with a counter steering system is
described by a nonlinear bicycle model. The NMPC problem is
formulated taking into account the obstacles description as
inequality constraints which will be updated at each
sampling time based on a laser scanner detection. The
nonlinear optimal control problem (NOCP) is efficiently
solved  by a combined multiple-shooting and collocation
method.  Experimentation results illustrate the viability
of our approach for active autonomous steering in avoiding
spontaneous obstacles.

Evgeniya Drozdova2, Siegbert Hopfgarten1, Evgeny Lazutkin1, Pu Li1
1Technische Universität Ilmenau, Group Simulation and Optimal Processes, Germany, 2Moscow Power Engineering Institute (National Research University), Russia

Recent investigations on the longitudinal and lateral
control of wheeled autonomous vehicles are reported. A
model-based design, which employs flatness-based techniques
is first introduced via a simplified model. It depends on
some physical parameters, like cornering stiffness
coefficients of the tires, friction coefficient of the
road, \dots, which are notoriously difficult to identify.
Then a model-free control strategy, which exploits the flat
outputs, is proposed. Those outputs also depend on physical
parameters which are poorly known, \textit{i.e.}, the
vehicle mass and inertia and the position of the center of
gravity. A totally model-free control law is therefore
adopted. It uses natural output variables, namely the
longitudinal velocity and the lateral deviation of the
vehicle. This last method, which is easily understandable
and implementable, ensures a robust trajectory tracking
problem in both longitudinal and lateral dynamics.

Brigitte D'Andrea-Novel1, Lghani Menhour2, Michel Fliess3,5, Hugues Mounier4
1Centre de Robotique, MINES ParisTech & PSL Research University, France, 2Université de Reims Champagne-Ardenne, IUT de Troyes, France, 3LIX (CNRS, UMR 7161), École polytechnique, France, 4L2S (UMR 8506), CNRS – Supélec – Université Paris-Sud, France, 5AL.I.E.N. (ALg`ebre pour Identification et Estimation Numériques), France




Friday, July 1st

We research on autonomous mobile robots with a seamless integration of
perception, cognition, and action. In this talk, I will first introduce
our CoBot service robots and their novel localization and symbiotic
autonomy, which enable them to consistently move in our buildings, now for
more than 1,000km. I will then introduce the CoBot robots as novel
mobile data collectors of vital information of our buildings, and present
their data representation, their active data gathering algorithm, and the
particular use of the gathered WiFi data by CoBot. I will further present
an overview of multiple human-robot interaction contributions, and detail
the use and planning for language-based complex commands. I will then
conclude with some philosophical and technical points on my view on  the
future of autonomous robots in our environments.

The presented work is joint with my CORAL research group, and in
particular refers to the past PhD theses of Joydeep Biswas, Stephanie
Rosenthal, and Richard Wang, and recent work of Vittorio Perera.

Prof. Manuela Veloso, Carnegie Mellon University


Abstract—Simultaneous localization and mapping (SLAM) is
vital for autonomous robot navigation. The robot must build
a map of its environment while tracking its own motion
through that map. There are many ways to approach the
problem, mostly based on the sequential probabilistic
approach, based around extended Kalman filter (EKF) or the
Rao-Blackwellized particle filter. In order to improve the
SLAM solution and to overcome some of the (EKF) and (PF)
limitations, especially when the process and observation
models contain uncertain parameters, we propose to use a
robust approach to solve the SLAM problem based on variable
structure theory. The new alternative called      Smooth
Variable Structure Filter (SVSF) is a predictor corrector
estimator based on sliding mode control and estimation
concepts. It has been demonstrated that the (SVSF) is
stable and very robust face modeling uncertainties and
noises. Visual SVSF-SLAM is implemented, validated and
compared with EKF-SLAM filter. The comparison proofs the
efficient and the robustness of localization and mapping
using SVSF-SLAM. 

Allam Ahmed1, Abdelkarim Nemra1, Hamerlain Mustapha2
1Ecole Militaire Polytechnique, Algeria, 2Division Robotique CDTA, Algeria

We present a 3D mesh surface navigation system for mobile
robots. This system uses a 3D point cloud to reconstruct a
triangle mesh of the environment in real time that is
enriched with a graph structure to represent local
connectivity. This Navigation Mesh is then analyzed for
roughness and trafficability and used for online path
planning. The presented approach is evaluated with a
VolksBot XT platform in a real life outdoor environment.

Sebastian Pütz1, Thomas Wiemann1, Sprickerhof Jochen1, Joachim Hertzberg1,2
1Osnabrück University, Germany, 2DFKI Robotics Innovation Center, Osnabrück Branch, Germany

Automatic surface reconstruction from point cloud data is
an active field of research in robotics, as polygonal
representations are compact and geometrically precise.
Standard meshing algorithms produce many redundant
triangles. Therefore methods for optimization are required.
In this paper we present and evaluate a mesh optimization
algorithm for robotic applications that was specially
designed to exploit the planar structure of typical indoor
environments.

Thomas Wiemann1, Kai Lingemann2, Joachim Hertzberg1,2
1Osnabrück University, Germany, 2DFKI Robotics Innovation Center, Osnabrück Branch, Germany



Topological maps have many applications in robotics.
Matching two topological maps from the same environment can
be used for map merging, place detection, map evaluation
and other purposes. In this paper we present an approach to
match two corresponding edges from two Topology Graphs to
each other based on the actual path with which the vertices
of the edges are connected in the underlying 2D grid maps.
We perform experiments with two artificial maps as well as
with four maps from the RoboCup Rescue WorldCup 2010.

Sören Schwertfeger, Tianyan Yu
ShanghaiTech University, China

This paper presents a large-scale 3D environment mapping
solution for mobile robots that is based on hybrid
metric-topological maps. If a robot performs simultaneous
localization and mapping (SLAM) while exploring an unknown
environment, sometimes loops are closed and the whole SLAM
graph has to be optimized. If a conventional occupancy grid
mapping algorithm using a monolithic map is used, the whole
occupancy grid map has to be rebuilt after optimization,
which for large maps can easily become too time consuming
for real-time operation. In the same way, path planning on
very large occupancy grid maps can become computationally
too expensive. Hybrid metric-topological maps can solve
both problems. The global metric map is divided into
sub-maps and a global topological graph is formed on the
map. This allows recomputing only isolated areas of the
map, whereas others can remain unchanged. The topological
graph allows efficient path planning on the hybrid map. We
show that the hybrid mapping approach presented here is
considerably faster than conventional methods. Within the
same time, it can generate more detailed maps of large
environments. The computation time for maps with identical
level of detail can be improved by up to two orders of
magnitude.

Patrik Schmuck, Sebastian Andreas Scherer, Andreas Zell
Chair of Cognitive Systems, Eberhard Karls Universität Tübingen, Germany

As robots leave the simple and static environments to more
complex and dynamic ones, 
they will have to improve their localisation abilities and
to deal with heterogeneous and imprecise data. 
In this paper, we present a general cooperative framework
designed to
localize in an absolute way a fleet of heterogeneous
vehicles. 
Depending on the sensors it embeds, each vehicle localize
itself
using a GNSS system (typically GPS),
an orientation system (a compass for instance),
the detection of the others robots in the
neighbourhood (typically with a LIDAR) and the detection of
visible geo-referenced features in the map (eg. wall,
poles,
etc...). 
These map features are often imprecise (as is
typically the case with collaborative public maps such as
OpenStreetMap). Our
approach allows to update these features positions in the
same framework.
We first present the filtering approach we developed to
solve the
classical over-convergence problem using the SCI (Split
Covariance
Intersection) filter.  
Map feature relative detection being simultaneously the
main
information source as well as compute-time expensive,
we show how in the same framework we optimize resource
usage
thanks to an entropy optimization strategy which avoids all
sensor data fusion and instead selects the best one at each
time step.

Laurent Delobel, Romuald Aufrère, Roland Chapuis, Thierry Chateau
Institut Pascal, Université Blaise Pascal, France

This paper applies Posterior Cramer-Rao Bound theory to the
SLAM problem to measure the information supplied by
different sensor modalities over time. Range-only,
bearing-only and full range-bearing sensors were
considered, as well as the gains in information achieved by
using multiple sensors in centralised co-operative SLAM. An
efficient recursive formula was used to compute the bound
for a variety of simulated scenarios, and its validity
verified by comparing the bound with the second-order error
performance of FastSLAM 2.0 and the EKF.

Daniel Devishtan Selvaratnam1, Iman Shames1, Branko Ristic2, Jonathan H. Manton1
1Department of Electrical and Electronic Engineering, University of Melbourne, 2Australia, School of Engineering, RMIT University, Australia



In nuclear facilities, such as the experimental fusion
reactor ITER, the cargo transfer operations are performed
by autonomous guided vehicles under remote supervision. In
ITER, these vehicles can reach up to 100 tons and, with a
rhombic-like configuration, have to move in cluttered
scenarios. In case of failure, the vehicles have to be
manually guided. This paper presents three solutions for
the teleoperation of rhombic-like vehicles. Two set of
devices were used to test each solution: one is based on a
gamepad and the other is based on a joystick with a
rotational disc specially designed for this purpose. The
solutions were experimented by the developer and by 12
users without prior experience on rhombic-like vehicles.
The experiments were performed in a software simulator that
provides 2D maps of the test facility and simulates the
kinematics of the vehicles in real time. The main
conclusions are reported.

Pedro Lopes1, Alberto Vale1, Rodrigo Ventura2
1Instituto de Plasmas e Fusão Nuclear, Instituto Superior Técnico, Universidade de Lisboa, Portugal, 2Institute for Systems and Robotics, Instituto Superior Técnico, Universidade de Lisboa, Portugal

Carsharing programs provide an alternative to private
vehicle ownership. Combining carsharing programs with
autonomous vehicles would improve user access to vehicles
thereby removing one of the main challenges these programs
face for widescale adoption. While the ability to easily
move cars to meet demand would be significant for
carsharing programs, if implemented incorrectly it could
lead to worse system performance. In this paper, we seek to
improve the performance of a fleet of shared autonomous
vehicles through improved matching of vehicles to
passengers requesting rides. We consider carsharing with
autonomous vehicles as an assignment problem and examine
four different methods for matching cars to users in a
dynamic setting. We show how applying a recent algorithm
(SCRAM) for minimizing the maximal edge in a perfect
matching can result in a more efficient,  reliable, and
fair carsharing system. Our results highlight some of the
problems with greedy or decentralized approaches.
Introducing a centralized system creates the possibility
for users to strategically mis-report their locations and
improve their expected wait time so we provide a proof
demonstrating that cancellation fees can be applied to
eliminate the incentive to mis-report location.

Josiah Hanna1, Michael Albert1, Donna Chen2, Peter Stone1
1Computer Science Department, University of Texas at Austin, USA 2Department of Civil & Environmental Engineering, University of Virginia, USA

Road roughness detection on the highway networks is
considered to be vital in order to ensure driving comfort
and safety. High-speed profilometers are developed in order
to be able to monitor road roughness on the highways
without affecting the normal traffic flow. This paper
focuses on the improvement and the implementation of
TRRL-type high-speed laser profilometers. In the presented
work, the original TRRL design is made more compact in
order to allow faster operating speeds. The error analysis
seen in the original work is extended with the changed
geometric design. It is observed that the factor that
affects the measurement accuracy the most is surface
texture due to its randomness. Therefore the paper proposes
a new method which eliminates the texture-caused errors by
modelling them with quadratic functions. The performance of
the presented profilometer is evaluated by conducting
experiments on a road with a known true profile. The
accuracy and the repeatability of the system show that the
presented profilometer can be used for measuring true
profiles with some further improvement.

Furkan Kilic, Joachim Hilsmann
measX GmbH & Co. KG, Germany

Mobile manipulators are intended to be deployed in domestic
and industrial environments where they will carry out tasks
that require physical interaction with the surrounding
world, for example, picking or handing over fragile
objects. In-hand slippage, i.e. a grasped object moving
within the robot's grasp, is inherent to many of these
tasks and thus, a robot's ability to detect a slippage is
vital for executing a manipulation task successfully. In
this paper, we develop a slip detection approach which is
based on the robot's tactile sensors, a force/torque sensor
and a combination thereof. The evaluation of our approach,
carried out on the Care-O-bot 3 platform, highly suggests
that the actions and motions performed by the robot during
grasping should be taken into account during slip detection
for improved performance. Based on this insight, we propose
an in-hand slip detection architecture that is able to
adapt to the current robot's actions at run time.

Jose Manuel Sanchez Loza, Sven Schneider, Nico Hochgeschwender, Gerhard Kraetzschmar, Paul Plöger
Department of Computer Science, Bonn-Rhein-Sieg University, Germany