Conference PaperPDF Available

Detecting Water Reflection Symmetries in Point Clouds for Camera Position Calibration in Unmanned Surface Vehicles

Authors:

Abstract and Figures

The development of autonomous vehicles has seen considerable advances over the past decade. However, specific challenges remain in the area of autonomous waterborne navigation. Two key aspects in autonomous surface vehicles are sensor calibration and segmentation of water surface. Cameras and other sensors in a car or drone can be installed accurately in a specific position and orientation. In a large vessel, this is not always possible, as sensors might be installed around the vessel or on masts. Taking advantage of the medium in which these vehicles operate, the water plane can be used as a reference for different sensors to calibrate their orientation. This allows more accurate localization of obstacles of objects. State-of-the-art deep learning techniques have been successfully applied for water surface segmentation in open sea. However, in other environments such as small rivers or lakes with still waters, a different approach might enable more accurate water surface estimation. We propose a method to estimate the water plane based on the detection of local symmetry planes that naturally occur when objects are reflected in the water. By using a point cloud generated with a stereo camera, we are able to accurately estimate the water level and, at the same time, calibrate the camera position and improve the localization of obstacles. We assume that an approximate position and orientation of the camera is known with respect to the sea level. We demonstrate the efficiency of our method with data obtained in the Aura river, Finland, with our prototype vessel facing both the riverside and the center of the river.
Content may be subject to copyright.
Detecting Water Reflection Symmetries in Point Clouds for
Camera Position Calibration in Unmanned Surface Vehicles
L. Qingqing1,2*, J. Pe ˜
na Queralta1*, T. Nguyen Gia1, Z. Zou2, H. Tenhunen3and T. Westerlund1
1Department of Future Technologies, University of Turku, Finland
2School of Information Science and Technology, Fudan Universtiy, China
3Department of Electronics, KTH Royal Institute of Technology, Sweden
Emails: 1{jopequ, tunggi, tovewe}@utu.fi, 2{qingqingli16, zhuo}@fudan.edu.cn, 3hannu@kth.se
Abstract—The development of autonomous vehicles has seen
considerable advances over the past decade. However, specific
challenges remain in the area of autonomous waterborne nav-
igation. Two key aspects in autonomous surface vehicles are
sensor calibration and segmentation of water surface. Cameras
and other sensors in a car or drone can be installed accurately
in a specific position and orientation. In a large vessel, this is not
always possible, as sensors might be installed around the vessel
or on masts. Taking advantage of the medium in which these
vehicles operate, the water plane can be used as a reference
for different sensors to calibrate their orientation. This allows
more accurate localization of obstacles of objects. State-of-the-art
deep learning techniques have been successfully applied for water
surface segmentation in open sea. However, in other environments
such as small rivers or lakes with still waters, a different approach
might enable more accurate water surface estimation. We propose
a method to estimate the water plane based on the detection of
local symmetry planes that naturally occur when objects are
reflected in the water. By using a point cloud generated with a
stereo camera, we are able to accurately estimate the water level
and, at the same time, calibrate the camera position and improve
the localization of obstacles. We assume that an approximate
position and orientation of the camera is known with respect to
the sea level. We demonstrate the efficiency of our method with
data obtained in the Aura river, Finland, with our prototype
vessel facing both the riverside and the center of the river.
Index Terms—Camera Calibration; Reflection Symmetry;
Symmetries; Stereo Vision; Intel RealSense; Point Cloud; PCL;
ROS; Autonomous Vessels; USV; Surface Vehicles; Autonomous
Surface Vehicles; Autonomous Vehicles;
I. INTRODUCTION
The past decade has seen a boost in the development
of autonomous waterborne vehicles, or unmanned surface
vehicles (USV), including autonomous surface vessels [1]–[3]
or autonomous ferries [4], [5]. This has happened under the
umbrella of a general trend in the development of autonomous
systems [6], [7]. In an autonomous vessel, it is essential that
cameras and other sensors are able to autonomously calibrate
their orientation or even relative positioning [8], [9]. In this
work, we focus on the estimation of the water surface plane
by detecting local symmetries in a point cloud obtained with a
stereo camera. This enables an accurate orientation estimation
of cameras installed on-board a vessel, and therefore more
accurate obstacle localization. Furthermore, the water plane
*: These authors contributed equally to this work.
Fig. 1. Prototype vessel TIERS1 used as sensing platform for testing.
can be used as reference for collaborative mapping in multi-
robot systems [10], or as an orientation reference in formation
control algorithms [11], [12].
In a large autonomous vessel, it is often a complex task to
accurately install and deploy small sensors such as cameras.
For example, a small orientation error in cameras placed on
the mast of a very long vessel can cause a significant error
in positioning a detected obstacle with respect to the vessel.
In addition, a large ship would require the installation of an
analogously large number of cameras or sensors, and therefore
manual calibration of their position and orientation might
be unfeasible. Therefore, it is essential to have algorithms
that enable automatic and real-time camera calibration. Even
though we focus our work in river and lake operations, similar
approaches can be used in calm seas such as those in the
Finnish archipelago, where multiple ferries operate. It has been
in this archipelago where the world’s first autonomous ferry
was unveiled [8]. Therefore, when we refer to large vessels
we also take into account city ferries that operate on rivers,
ships that navigate on lakes and ferries that transport people,
vehicles or goods between close islands in an archipelago.
In terms of vessel dynamics, roll oscillation in ships is
a phenomenon that does not commonly occur in ground
vehicles and poses critical challenges to typical navigation
and object detection approaches [13]. Roll oscillations sig-
nificantly affect vision-based localization, mapping and ob-
ject detection algorithms. Inertial measurement units, and in
particular accelerometers and gyroscopes, can be used to
estimate the roll of a ship and the orientation of individual
cameras. Nonetheless, this would require either the installation
of inertial sensors on each camera separately, or the design
of a robust method for estimating the relative orientation of
different cameras. Instead, we propose the analysis of stereo
images to estimate the orientation of the cameras based on
their position with respect to the water surface. Then, the
orientation of monocular cameras can be estimated via object
detection and matching between different cameras.
The detection of the water surface plane poses different
challenges in open sea and on quiet waters such as rivers
and lakes. In the former case, the height and movement of
waves can have a significant impact on the performance of
different methods. In the latter case, the reflective properties
of still waters, which act as a mirror, might result in a complex
distinction between objects above and below the water surface.
However, this reflection can be exploited to find the water
surface as a reflection plane in the image or a local symmetry
plane in a point cloud obtained from a stereo camera.
The methods we design and develop can be applied to au-
tonomous navigation in environments where water is reflective
enough and there are objects nearby that can be detected by
cameras on-board the vessel. This is the case of small rivers
and lakes such as those where city ferries typically operate.
The use of cameras instead of other sensors such as 3D lidars,
which are becoming increasingly popular in the development
of autonomous ground vehicles [14], [15], has been motivated
by the intrinsic limitation of light sensing in water. While water
in open seas can provide a limited number of returns for a 3D
lidar because of high waves, lidars are practically blind in still
waters where laser beams are almost entirely reflected.
The remainder of this paper is organized as follows. Section
II covers related works on symmetry plane estimation in
discrete sets of points, water surface segmentation with deep
learning methods and calibration of cameras in unmanned
surface vehicles. In Section III, we describe our algorithm for
estimating the water surface plane based on object reflections
near the coastline (or riverside). Section IV introduces our
prototype vessel TIERS1 and its sensor suite, as well as the
data acquisition and pre-processing methods, and delves into
the experimental results and their analysis, and we compare
the efficiency of our method for individual frames and using
previous frames estimations. Finally, Section V concludes the
work and outlines future work directions.
II. REL ATED WOR K
Even though research into autonomous surface vessels has
seen a rapid development over the past years, this is still a
relatively new research area with a correspondingly limited
number of previous research works. In this paper, we are
focusing on using stereo vision for estimating the relative
position of a camera with respect to the water surface plane.
In comparison with the problem of road detection and seg-
mentation in autonomous cars, segmentation of water surface
can pose additional challenges because of the reflective and
refractive qualities of water. To the authors’ best knowledge,
symmetry analysis of point cloud data to find the water level
surface based on object reflections has not been proposed
before. Due to the lack of previous work, in this section
we review related works in the areas of (i) vision-based
navigation and operation of autonomous vessels in general; (ii)
water surface detection and segmentation with vision-based
techniques; and (iii) estimation of approximate symmetry
planes from discrete point cloud data.
Huntsberger et al. presented the first stereo vision-based
navigation system for autonomous surface vessels [16]. The
authors propose the use of stereo cameras as a low-latency
and real-time method for detecting obstacles above the sea
level. This is the envisioned application for our system as
well. However, Huntsberger et al. worked with a relatively
small boat and were able to install the camera array in a
known position with known orientation. We aim at providing
a flexible methodology for camera calibration that will enable
the installation of cameras in large vessels without accurate
knowledge of their orientation. Therefore, it is essential to
provide an accurate method for estimating camera orientation
in real time. In addition, it is worth noting that Huntsberger
et al. already acknowledge in their early work the challenge
that specular reflections can pose for cameras.
Bovcon et al. have also proposed a stereo-based obstacle
detection scheme for USVs [17]. A stereo-view semantic seg-
mentation is shown in their work to outperform state-of-the-art
methods that rely on monocular approaches and convolutional
neural networks. In terms of water edge detection, Wang et
al. previously proposed the combination of saliency detection
and motion estimation to find obstacles under an estimated
water edge [18]. Nonetheless, they assumed a clear distinction
between sky and water. The approach of Bovcon et al. is more
flexible and robust in the water edge detection, but is still
mostly limited to open sea. In our work, we do not assume
that water surface and sea intersect in the camera horizon as
this is often not the case in rivers and lakes.
State-of-the-art deep learning methods have been applied to
enable automatic water-body segmentation. However, to the
extent of our knowledge, this has been done mostly with satel-
lite or airborne imagery. Liu et al. presented a Segmentation-
based Convolutional Neural Network (SLS-CNN) model for
ship detection using Synthetic Aperture Radar (SAR) imagery
[19]. Other researchers have been applying convolutional
neural networks for water-land segmentation from satellite
images. Li et al. trained a novel deep neural network named
DeepUNet for pixel-level sea-land segmentation [20]. In the
same direction, Miao et al. proposed a restricted receptive field
deconvolution network (RRF DeconvNet) [21].
A different approach utilized by Hilsenstein was to use
thermographic stereo vision for reconstruction of water waves
surface [22]. The author exploits the complex temperature
patterns that can be seen in water surfaces under infrared light,
as compared to transparent water seen within the visible spec-
trum. This is a promising approach for open sea applications,
but has a more limited impact on navigation in still waters.
Most of the previous works on autonomous vessels or USV
Algorithm 1: Water surface plane estimation in ROS.
Subscribe to:
/camera/color/points;
/lidar(0,1)/scan;
Publish to:
/water/surface;
/water/height;
/calibration/camera(y aw, pitch, roll);
while True do
// Estimate distance to riverside
distance to coastline =F(lidar scan, gnss data);
filtered pointcloud =F(stereo pointcloud);
// Estimate water level plane.
water height =find symm(f iltered pointcloud);
roll estimate =
find symm(water height, f iltered pointcloud);
pitch estimate =find symm(filter ed pointcloud);
// Use compass to obtain the yaw.
yaw estimate =from compass();
// Combine to obtain camera orientation.
camera orientation =
combine(water line, roll estimate, pitch estimate);
has been focused on open sea navigation. However, in this
paper we put an emphasis on the specific characteristics of
waterborne navigation in still waters. As quiet waters have
good specular properties, we propose to exploit this in order
to estimate the water level by finding local symmetries in point
cloud data. This is a problem that has been previously studied
in the fields of computer vision and computer graphics as
a step for modelling objects for several decades [23]. More
recently, Li et al. proposed a method specifically meant for
boundary improvement in models made of discrete point sets
[24]. For larger dimensions, such as point clouds that include
color or other non-spatial information, Nagar et al. provide
an algorithm for detecting approximate reflection symmetries
[25]. In our work, we take inspiration from works on symmetry
detection in order to detect the water surface plane.
III. WATER SU RFACE PLANE ESTIMATION
In this section, we outline the methodology for estimating
the water surface plane based on the stereo camera point cloud.
The algorithm we propose utilizes either lidar data or GNSS
sensor data to estimate the distance of the boat with respect
to the lakeside or river banks, depending on the application
scenario. This information is used in order to make initial
filtering of the stereo point cloud. The method we propose is
described in Algorithm 1, and can be broadly divided into four
steps: (i) point cloud filtering, (ii) camera height estimation,
(iii) camera roll estimation, and (iv) camera pitch estimation.
In this paper, we show results on camera height and roll
estimation. The approach we propose can be extended to add
the pitch estimation, and we will account for it in future work.
In the algorithm, Fdenotes an undetermined function.
A. Point cloud filtering
The first step is to pre-process data and apply some filters
to the point cloud in order to reduce the number of points and
reduce the computational team necessary to run our proposed
algorithm. This is essential to enable real-time operation.
Taking into account that a considerable part of the point cloud
does not appear in the reflection, we use GNSS or lidar data
to estimate the distance to the lakeside or river banks. Then,
this distance is used to filter points so that we only take into
accounts objects near the coastline, which is where reflections
occur. Based on this distance, points are filtered in two ways:
by absolute distance to the boat, and by vertical distance. If
the ship is near the coastline, then only objects with relatively
small height are considered, as there would not be enough field
of view to perceive the reflection of tall objects. The opposite
applies when the ship is far from the water-land boundary, as
there might be too much noise around it with objects being
too small to be identifiable while big objects have more clear
reflections. These phenomena can be observed in Figures 4 and
5. In addition, if the point cloud is very dense, we perform a
downsampling operation to speed up the analysis.
B. Camera height estimation
The next step is to estimate the height of the camera with
respect to the water surface. In this paper, we assume that
the camera pitch and roll are known beforehand within a
certain and small range. This is a practical assumption as
these parameters can be roughly estimated when cameras are
installed on the ship with errors of a few degrees. We also
assume that the camera height is known to be within a certain
interval. If this information is not available, the same method
can still be applied but the computational complexity and
execution time increase significantly.
After filtering, suppose we have a point set S={xi}N
i=1 of
size N. We assume that the point set coordinates are adjusted
according to the estimated pitch and roll of the camera.
Therefore, we suppose that the water surface plane is almost
horizontal. In order to follow the coordinate system in which
the Intel RealSense’s point cloud is defined, we assume that
the height is given by coordinate y,zprovides the depth and
xdescribes the lateral distance with respect to the camera.
Then, given a pre-defined interval (hl, hh)where the camera
is assumed to be, we choose a step hand calculate, for
each height h=hmin +kh, the reflection of all points such
that xiy> h and xiyh < hth. The constant hth R+
is a threshold defined as a function of the distance to the
coastline, and k∈ {0,...,(hhhl)/h}is an integer that
used to sample the interval (hl, hh). We estimate the water
level height hwto be defined by:
(1)
hw=h:h=hmin +kh
= argmin
k∈{0,..., hhhl
h}
1
NkX
xiy>h
xiyh<hth
xR
ikdTree(xR
i)
2
where xR
i=x2(xiyh)uxis the reflection of point xwith
respect to a horizontal plane perpendicular to uxat height
LIDAR1LIDAR0
INFRA0 INFRA1 RGB02Dto3D
IntelRealsense
POINTS
DISTANCETOCOASTLINE
ABSOLUTE
POSITION
GNSS
RGB1 RGB2
OBJECTDETECTION
ANDMATCHING
WATERSURFACE
PLANEESTIMATION
STEREOCAMERA
ORIENTATION
CAMERASRELATIVE
POSITION/ORIENTATION
POSITIONING
OBJECTDETECTIONANDCOLLISIONAVOIDANCE
Fig. 2. Sensors installed on-board the TIERS1 prototype vessel and envisioned situational awareness data flow. This paper focuses on the processes marked
in red, mainly in water surface estimation and stereo camera orientation.
Yaw Pitch
Roll
Fig. 3. Illustration of pitch, roll and yaw on a vessel.
h,uxis the unit vector that defines the xaxis, and Nkis
the number of points within the height threshold in order to
normalize the error. The value hth is chosen so that only
reflections of objects near the water surface are taken into
account when the ship is near the coastline, and bigger objects
are accounted for otherwise. We only take into account points
above the water surface and try to find their reflection in the
point cloud. A KD-tree search algorithm is used to find the
nearest point in the point cloud to the expected reflection.
C. Camera roll and pitch estimation
Once we have obtained an approximate camera height
estimation, we perform the same symmetry analysis on a
subset of the point cloud around the symmetry plane in order
to adjust the roll and pitch angles. Let hc=hwbe the
approximate camera height and water level height obtained in
the previous step, and φand θthe camera roll and pitch
angles, respectively. The yaw angle ψis not taken into account
as the water plane is invariant to the camera yaw and it can be
estimated with a magnetometer or other sensors. The normal
vector of the reflection plane will be defined by
nr= cos φcos θux+ sin φuy+ sin θuz(2)
and we assume that the distance between the camera and the
water level is the height obtained in the previous step. This
assumption holds without incurring in a significant error if
the roll and pitch angles are small, as we are assuming, and if
the boat is not too far from the coastline, so that the camera
horizon is above the water level. This is a logic expectation
as we are developing a method for operation in river, lakes
or archipelagos, where the distance between the boat and the
nearest point of land should never be too large or otherwise
there would be no reflections in the water to take into account.
Following the same reasoning, we can approximate a point’s
distance to the plane drand its reflection by
xR
i=xi2drnr, drxiysin θsin φ(3)
We have denoted the pitch and roll angles with a negative sign
so that φ, θ refer to the angles that define the water plane as
seen from the camera. We can then estimate the roll and pitch
angles minimizing an error function analogous to that of Eq.
1, where we would find the argument of the minimum angles
within some predefined intervals.
This is a simple approach to calculate the water level, which
we have used as a proof of concept for our proposed algorithm.
More elaborate methods such as those defined by Nagar et al.
can be adapted [25]. However, this is out of the scope of this
paper and we have focused on demonstrating the possibility of
estimating the water surface plane based on water reflections.
Future works will focus on the effect of camera pitch and roll
on the estimation of the water level plane.
IV. EXP ERIMENT AND RESU LTS
In order to test the efficiency of our proposed methods,
we have obtained a series of images in the Aura river,
Turku, Finland. With our prototype vessel, we compare the
performance of our algorithm in two situations. First, when
the bow is pointing at the riverside, with clear reflection in
the water of walls and trees in the river bank. Second, when
the bow is pointing to the center of the river, with only big
trees from the river banks being visible and reflected. These
two situations are illustrated in Figures 4 and 5, respectively. In
the first image, the light source is behind the camera creating
a clear view and reflection. In the second image, the light
source is partly in front of the camera, and therefore colors
are less evident. We have used these two light settings to test
the robustness of our methods.
A. Sensing Platform: TIERS1
We have used a small ship model as a platform for gathering
data and carrying out experiments. The ship, TIERS1, is a
model based on an Aerokits Sea Queen model boat, and has
Fig. 4. Prototype looking towards the riverside: RGB view [l]; RGB point cloud from camera point of view [c]; Filtered point cloud from a side plane [r].
Fig. 5. Prototype looking towards the river center: RGB view [l]; RGB point cloud from camera point of view [c]; Filtered point cloud from a side plane [r].
been built at the Turku Intelligent Embedded and Robotic
Systems (TIERS) Group. The ship has a length of 1170mm
and a beam of 370mm. The draft is approximately 120mm if
loaded. An image of the ship appears in Figure 1.
The following hardware has been installed on-board the
ship: (i) 2 x RPLidar A1M8, one of them tilted 9 degrees in
order to detect obstacles at the water surface level immediately
in front of the boat’s bow; (ii) 1 x Intel RealSense D435 stereo
camera, with one RGB camera and two IR cameras; (iii) 2
x Logitech c270 USB cameras; (iv) 1 x Ublox M8N GNSS
sensor; (v) Intel UPS-GWS01 IoT edge gateway as the main
on-board computer, with 4x1.4GHz cores Intel Atom CPU,
Intel HD Graphics and 4GB RAM. The Ublox GNSS sensor
also has a built-in compass. The computer, lidars and cameras
are powered from an 8.6Ah AGM battery. The boat motor,
servo motor and radio receiver are powered by a separate
8.4V, 3800mAh NiMH battery. All the sensors are installed
on a 380mm mast with a total ship height of 600mm.
The on-board computer runs Ubuntu 16.04 and ROS Ki-
netic, which is used as a framework for interfacing with all
sensors. We use Intel’s realsense camera, Slamtec’s rplidar
and nmea navsat driver ROS packages. On top of that, we
run our own ROS package. As one of the lidars is tilted 9
degrees towards the ship bow, we apply a transformation to
publish 3D point cloud data from the 2D lidar data. We use
this information and the Realsense’s point cloud to estimate
the waterline and water surface level with PCL, which are
then published with their own respective topics. Figures 4 and
5 show the stereo-based point cloud (center) and a side view
of the filtered point cloud (right).
0.55 0.60 0.65 0.70 0.75
340
360
380
Vertical distance to camera (m)
#Points
0.016
0.018
0.020
0.022
0.024
Errors
Fig. 6. Water plane height estimation error for data in Figure 4.
ROS (Robot Operating system) is an open source oper-
ating system for robots, which provides a publish-subscribe
communication framework that can quickly build distributed
computing systems [26]. The goal of ROS is to provide
algorithm reuse support for robot research and development.
PCL (Point Cloud Library) is a cross-platform open source
C++ library, which implements common algorithms and data
structures of point clouds [27]. It can realize point cloud
acquisition, filtering, segmentation, registration, retrieval, fea-
ture extraction, recognition, tracking, surface reconstruction,
visualization and so on. If OpenCV is the crystallization of
2D information acquisition and processing, PCL has the same
position in 3D information acquisition and processing.
B. Analysis of Results
We have applied the water height estimation in (1) to the
point cloud data included in Figures 4 and 5. The computation
of the error according to (1) is shown in Figures 6 and 7. The
0.40 0.45 0.50 0.55 0.60 0.65 0.70 0.75 0.80
2,000
2,200
2,400
2,600
Vertical distance to camera (m)
#Points
0.22
0.23
0.24
0.25
0.26
Errors
Fig. 7. Water plane height estimation error for data in Figure 5.
water height is estimated towards the minimum of the blue
curve, and therefore we obtain a height of 0.6 to 0.65 m in
both cases, with more noise in the first case.
In the situation where the ship is close to the river bank, we
have used a height threshold hth = 0.5m as reflections are
more clear for objects close to the water level. In the case of
the ship bow pointing towards the center of the river, we have
used hth=3 m to account for taller trees and their reflections.
Analogously, we have used absolute threshold distances of 5
and 8m, respectively, taking into account the distance to the
river bank estimated from the lidar data. These constants have
an impact on the number of points that are used to calculate the
error. The number of points for each potential height analyzed
is shown in red in the graphs. We have added this information
as the method would not be reliable if the number of points
found within the predefined height thresholds is too low.
The original size of the point cloud in the first situation was
of 175985 points. From these, after filtering and downsampling
we utilized a total of 9009 points to estimate the water height.
In the second scenario, the original number of points was
183806 and the final number after filtering was 11164.
V. CONCLUSION AND FUTURE WORK
We presented a methodology for estimating water surface
plane in an autonomous boat via point cloud analysis. The
point cloud data was generated with a stereo camera and
an algorithm for finding local symmetry planes was applied.
These symmetry planes are caused by the specular properties
of still waters, such as those of lakes or rivers. An automated
and accurate calibration of cameras enables a correspondingly
accurate measurement of obstacles. Therefore, the situational
awareness and orientation of individual cameras can have
a significant impact on the performance of navigation and
collision avoidance algorithms in autonomous vessels.
We have tested our proposed algorithm in the Aura river,
Turku, Finland. Data has been gathered with a customized
small model boat. Different settings have been analyzed, with
the boat both pointing to the riverside and the center of the
river. In both cases, our algorithm has been able to estimate the
camera height. In future work, we will integrate this system
into an obstacle detection and avoidance scheme, and study
further the estimation of camera pitch and roll.
REFERENCES
[1] T. Statheros et al. Autonomous ship collision avoidance naviga-
tion concepts, technologies and techniques. Journal of Navigation,
61(1):129–142, 2008.
[2] B. E. Jose et al. Optimisation of autonomous ship manoeuvres applying
ant colony optimisation metaheuristic. Expert Systems with Applications,
39(11):10120 – 10139, 2012.
[3] A. Bassam et al. Experimental testing and simulations of an autonomous,
self-propulsion 2 and self-measuring tanker ship model. Ocean Engi-
neering, 2019.
[4] D. Henkel et al. Towards autonomous data ferry route design through
reinforcement learning. In 2008 International Symposium on a World
of Wireless, Mobile and Multimedia Networks, pages 1–6. IEEE, 2008.
[5] J. Leikas et al. Ethical framework for designing autonomous intelli-
gent systems. Journal of Open Innovation: Technology, Market, and
Complexity, 5(1):18, 2019.
[6] D. J. Fagnant et al. Preparing a nation for autonomous vehicles:
opportunities, barriers and policy recommendations. Transportation
Research Part A: Policy and Practice, 77:167–181, 2015.
[7] O. Levander. Autonomous ships on the high seas. IEEE Spectrum,
54(2):26–31, 2017.
[8] Rolls-Royce et al. Finferries’ falco world’s first fully autonomous ferry.
Finnferries, 2018.
[9] J. Villa Escusol et al. Autonomous and collaborative offshore robotics.
In Proceedings of the 2nd Annual SMACC Research Seminar 2017,
pages 57–59. Tampere University of Technology, 2017.
[10] J. Pe ˜
na Queralta et al. Collaborative mapping with ioe-based heteroge-
neous vehicles for enhanced situational awareness. In IEEE SAS, (2019).
[11] J. Pe ˜
na Queralta et al. Communication-free and index-free distributed
formation control algorithm for multi-robot systems. Procedia Computer
Science, 2019.
[12] C. McCord et al. Distributed Progressive Formation Control for Multi-
Agent Systems: 2D and 3D deployment of UAVs in ROS/Gazebo with
RotorS. In 2019 European Conference on Mobile Robots (ECMR).
[13] R. A. Ibrahim et al. Modeling of ship roll dynamics and its coupling
with heave and pitch. Mathematical Problems in Engineering, 2010.
[14] J. Zhang et al. Visual-lidar odometry and mapping: Low-drift, robust,
and fast. In 2015 IEEE International Conference on Robotics and
Automation (ICRA), pages 2174–2181. IEEE, 2015.
[15] B. Li et al. Vehicle detection from 3d lidar using fully convolutional
network. arXiv preprint arXiv:1608.07916, 2016.
[16] T. Huntsberger et al. Stereo vision–based navigation for autonomous
surface vessels. Journal of Field Robotics, 28(1):3–18, 2011.
[17] B. Bovcon et al. Obstacle detection for usvs by joint stereo-view
semantic segmentation. In 2018 IEEE/RSJ International Conference on
Intelligent Robots and Systems (IROS), pages 5807–5812, Oct 2018.
[18] H. Wang et al. Improvement in real-time obstacle detection system
for usv. In 2012 12th International Conference on Control Automation
Robotics Vision (ICARCV), pages 1317–1322, Dec 2012.
[19] Y. Liu et al. Sar ship detection using sea-land segmentation-based
convolutional neural network. In 2017 International Workshop on
Remote Sensing with Intelligent Processing (RSIP), May 2017.
[20] R. Li et al. Deepunet: A deep fully convolutional network for pixel-
level sea-land segmentation. IEEE Journal of Selected Topics in Applied
Earth Observations and Remote Sensing, 11(11):3954–3962, Nov 2018.
[21] Z. Miao et al. Automatic water-body segmentation from high-resolution
satellite images via deep networks. IEEE Geoscience and Remote
Sensing Letters, 15(4):602–606, April 2018.
[22] V. Hilsenstein. Surface reconstruction of water waves using thermo-
graphic stereo imaging. In Image and Vision Computing New Zealand,
volume 2. Citeseer, 2005.
[23] H. Schultz. Retrieving shape information from multiple images of a
specular surface. IEEE Transactions on Pattern Analysis and Machine
Intelligence, 16(2):195–201, 1994.
[24] L. Ming et al. Detecting approximate symmetries of discrete point
subsets. Computer-Aided Design, 40(1):76–93, 2008.
[25] R. Nagar et al. Detecting approximate reflection symmetry in a point
set using optimization on manifold. IEEE Transactions on Signal
Processing, 67(6):1582–1595, 2019.
[26] M. Quigley et al. Ros: an open-source robot operating system. In ICRA
workshop on open source software. Kobe, Japan, 2009.
[27] R. B. Rusu et al. 3D is here: Point cloud library (PCL). In 2011 IEEE
International Conference on Robotics and Automation, May 2011.
... Active research areas in TIERS include multi-robot coordination [1], [2], [3], [4], [5], swarm design [6], [7], [8], [9], UWB-based localization [10], [11], [12], [13], [14], [15], localization and navigation in unstructured environments [16], [17], [18], lightweight AI at the edge [19], [20], [21], [22], [23], distributed ledger technologies at the edge [24], [25], [26], [27], [28], [29], edge architectures [30], [31], [32], [33], [34], [35], offloading for mobile robots [36], [37], [38], [39], [40], [41], [42], LPWAN networks [43], [44], [45], [46], sensor fusion algorithms [47], [48], [49], and reinforcement and federated learning for multi-robot systems [50], [51], [52], [53]. ...
... Several works were also published on the topic of calibrating stereo systems for USVs [22][23][24][25][26]. Their approaches range from exploiting features such as horizon estimation to calibrate a wide-baseline stereo system to using the water surface as a reference for calibration or employing deep learning to extract and match features from image data. ...
Article
Full-text available
Camera systems in autonomous vehicles are subject to various sources of anticipated and unanticipated mechanical stress (vibration, rough handling, collisions) in real-world conditions. Even moderate changes in camera geometry due to mechanical stress decalibrate multi-camera systems and corrupt downstream applications like depth perception. We propose an on-the-fly stereo recalibration method applicable in real-world autonomous vehicles. The method is comprised of two parts. First, in optimization step, external camera parameters are optimized with the goal to maximise the amount of recovered depth pixels. In the second step, external sensor is used to adjust the scaling of the optimized camera model. The method is lightweight and fast enough to run in parallel with stereo estimation, thus allowing an on-the-fly recalibration. Our extensive experimental analysis shows that our method achieves stereo reconstruction better or on par with manual calibration. If our method is used on a sequence of images, the quality of calibration can be improved even further.
Article
In this paper, collision avoidance (CA) scheme for unmanned surface vehicles (USVs) under complex shallow sea environments which contain static sea surface (Static), undersea obstacles (UO) and surface island with reefs (IR) is proposed. The main challenge of this paper is that CA objects not only include surface obstacles, UO and IR, but more importantly, they will be affected by dynamic water level. It is difficult, if not impossible, to employ conventional CA schemes for USVs. The salient features of the proposed scheme are: 1) A UO model which incorporates time-varying water level is developed. 2) The smoothing edge (SE) method of island of IR that is based on fuzzy Gauss mixture model is enhanced by introducing fuzzy membership to Gaussian mixture model. 3) A real-time collision probability (RTCP) algorithm under IR with time-varying water level which obeys the Poisson and Gauss distribution is developed. By combining the UO-FMM and the SE-RTCP, the proposed CA scheme is able to handle uncertainties in complex shallow sea environments. Comparative studies with the state of the art demonstrate that the proposed CA scheme is superior in terms of safety and yaw cost consumption.
Conference Paper
Full-text available
Coordination of multiple robots in order to cooperatively perform a given task requires a certain distribution of the different units in space. Furthermore, individual robots, or agents, might have different tasks, or positions, assigned. Formation control algorithms might rely on a priori information, a centralized controller, or communication among the agents to assign roles. Distributed approaches that only need local interaction between agents have limited possibilities, such as flocks where agents actively control the distance to neighboring agents. Alternatively, two-way local communication has been applied to progressively assign roles and converge towards a given configuration. We propose a progressive assignment algorithm and formation control scheme that extends leader-follower formations in order to enable cooperation of multiple robots with minimal, one-way, local communication between agents. The proposed algorithm progressively generates a directed, locally convex, path graph to uniquely assign formation positions to all agents. The low computational complexity of our algorithm enables its implementation in resource-limited devices. Agents only require information about neighboring agents and be able to locally broadcast their status. This algorithm enables almost arbitrary two-dimensional configurations, with the only limitation being the sensing range enabling the definition of a series of convex hulls in a certain subset of agents such that agents sharing an edge in the hull are able to sense each other. Moreover, we propose a methodology for deploying agents to an arbitrary three-dimensional configuration after the assignment process is made on the plane.
Article
Full-text available
Pattern formation algorithms for swarms of robots can find applications in many fields from surveillance and monitoring to rescue missions in post-disaster scenarios. Complex formation configurations can be of interest to be the central element in an exhibition or maximize surface coverage for surveillance of a specific area. Existing algorithms that enable complex configurations usually require a centralized control, a communication protocol among the swarm in order to achieve consensus, or predefined instructions for individual agents. Nonetheless, trivial shapes such as flocks can be accomplished with low sensing and interaction requirements. We propose a pattern formation algorithm that enables a variety of shape configurations with a distributed, communication-free and index-free implementation with collision avoidance. Our algorithm is based on a formation definition that does not require indexing of the agents. We show the potential of the algorithm by simulating the formation of non-trivial shapes such as a wedge and a T-shaped configuration. We compare the performance of the algorithm for single and double integrator models for the dynamics of the agents. Finally, we run a preliminary test of our algorithm by implementing it with a group of small cars equipped with a Lidar for sensing and orientation calculation. Full text available at: https://tiers.utu.fi/paper/ant2019
Conference Paper
Full-text available
The development of autonomous vehicles or advanced driving assistance platforms has had a great leap forward getting closer to human daily life over the last decade. Nevertheless, it is still challenging to achieve an efficient and fully autonomous vehicle or driving assistance platform due to many strict requirements and complex situations or unknown environments. One of the main remaining challenges is a robust situational awareness in autonomous vehicles in unknown environments. An autonomous system with a poor situation awareness due to low quantity or quality of data may directly or indirectly cause serious consequences. For instance, a person's life might be at risk due to a delay caused by a long or incorrect path planning of an autonomous ambulance. Internet of Everything (IoE) is currently becoming a prominent technology for many applications such as automation. In this paper, we propose an IoE-based architecture consisting of a heterogeneous team of cars and drones for enhancing situational awareness in autonomous cars, especially when dealing with critical cases of natural disasters. In particular, we show how an autonomous car can plan in advance the possible paths to a given destination, and send orders to other vehicles. These, in turn, perform terrain reconnaissance for avoiding obstacles and dealing with difficult situations. Together with a map merging algorithm deployed into the team, the proposed architecture can help to save traveling distance and time significantly in case of complex scenarios.
Article
Full-text available
To gain the potential benefit of autonomous intelligent systems, their design and development need to be aligned with fundamental values and ethical principles. We need new design approaches, methodologies and processes to deploy ethical thought and action in the contexts of autonomous intelligent systems. To open this discussion, this article presents a review of ethical principles in the context of artificial intelligence design, and introduces an ethical framework for designing autonomous intelligent systems. The framework is based on an iterative, multidisciplinary perspective yet a systematic discussion during an Autonomous Intelligent Systems (AIS) design process, and on relevant ethical principles for the concept design of autonomous systems. We propose using scenarios as a tool to capture the essential user’s or stakeholder’s specific qualitative information, which is needed for a systematic analysis of ethical issues in the specific design case.
Conference Paper
Full-text available
Reliable automatic ship detection in Synthetic Aperture Radar (SAR) imagery plays an important role in the surveillance of maritime activity. Apart from the well-known Spectral Residual (SR) and CFAR detector, there has emerged a novel method for SAR ship detection, based on the deep learning features. Within this paper, we present a framework of Sea-Land Segmentation-based Convolutional Neural Network (SLS-CNN) for ship detection that attempts to combine the SLS-CNN detector, saliency computation and corner features. For this, sea-land segmentation based on the heat map of SR saliency and probability distribution of the corner is applied, which is followed by SLS-CNN detector, and a final merged minimum bounding rectangles. The framework has been tested and assessed on ALOS PALSAR and TerraSAR-X imagery. Experimental results on representative SAR images of different kinds of ships demonstrate the efficiency and robustness of our proposed SLS-CNN detector.
Article
Improving the energy efficiency of ships has generated significant research interest due to the need to reduce operational costs and mitigate negative environmental impacts. Therefore, numerous energy saving technologies have been proposed, however, their overall performance needs to be carefully assessed before implementation. For assessing the energy saving potential of different technologies, autonomous ship models can be a powerful tool through model testing combined with numerical simulations. In this work, an autonomous, self-propelled and self-measuring free running ship model of an Ice Class tanker is developed. A series of experiments have been conducted which included bollard pull, shaft efficiency, naked-hull, self-propulsion, and manoeuvrability tests to investigate the efficiency improvement resulted from changing the ship operational trim and testing different bow designs. The experiments were conducted successfully proving the effectiveness and validity of the developed ship model. Alongside, a mathematical model for the time domain simulation of the developed autonomous ship model
Article
We propose an algorithm to detect approximate reflection symmetry present in a set of volumetrically distributed points belonging to $\mathbb{R}^d$ containing a distorted reflection symmetry pattern. We pose the problem of detecting approximate reflection symmetry as the problem of establishing correspondences between the points which are reflections of each other and we determine the reflection symmetry transformation. We formulate an optimization framework in which the problem of establishing the correspondences amounts to solving a linear assignment problem and the problem of determining the reflection symmetry transformation amounts to solving an optimization problem on a smooth Riemannian product manifold. The proposed approach estimates the symmetry from the geometry of the points and is descriptor independent. We evaluate the performance of the proposed approach on the standard benchmark dataset and achieve the state-of-the-art performance. We further show the robustness of our approach by varying the amount of distortion in a perfect reflection symmetry pattern where we perturb each point by a different amount of perturbation. We demonstrate the effectiveness of the method by applying it to the problem of 2-D and 3-D reflection symmetry detection along with comparisons.
Article
Water-body segmentation is an important issue in remote sensing and image interpretation. Classic methods for counteracting this problem usually include the construction of index features by combining different spectra, however, these methods are essentially rule-based and fail to take advantage of context information. Additionally, as the quality of image resolution improves, these methods are proved to be inadequate. With the rise of convolutional neural networks (CNN), the level of research about segmentation has taken a huge leap, but the field is still facing an increasing demand for data and the problem of blurring boundaries. In this letter, a new segmentation network called restricted receptive field deconvolution network (RRF DeconvNet) is proposed, with which to extract water bodies from high-resolution remote sensing images. Compared with natural images, remote sensing images have a weaker pixel neighborhood relativity; in consideration of this challenge, an RRF DeconvNet compresses the redundant layers in the original DeconvNet and no longer relies on a pretrained model. In addition, to tackle the blurring boundaries that occur in CNN, a new loss function called edges weighting loss is proposed to train segmentation networks, which has been shown to significantly sharpen the segmentation boundaries in results. Experiments, based on Google Earth images for water-body segmentation, are presented in this letter to prove our method.
Article
Semantic segmentation is a fundamental research in remote sensing image processing. Because of the complex maritime environment, the sea-land segmentation is a challenging task. Although the neural network has achieved excellent performance in semantic segmentation in the last years, there are a few of works using CNN for sea-land segmentation and the results could be further improved. This paper proposes a novel deep convolution neural network named DeepUNet. Like the U-Net, its structure has a contracting path and an expansive path to get high resolution output. But differently, the DeepUNet uses DownBlocks instead of convolution layers in the contracting path and uses UpBlock in the expansive path. The two novel blocks bring two new connections that are U-connection and Plus connection. They are promoted to get more precise segmentation results. To verify our network architecture, we made a new challenging sea-land dataset and compare the DeepUNet on it with the SegNet and the U-Net. Experimental results show that DeepUNet achieved good performance compared with other architectures, especially in high-resolution remote sensing imagery.