Content uploaded by Srijal Poojari
Author content
All content in this area was uploaded by Srijal Poojari on Oct 28, 2024
Content may be subject to copyright.
1
Outdoor Localization and Path Planning for
Repositioning an Autonomous Electric Scooter
Srijal Shekhar Poojari , Member, IEEE, Jaxon Lee , and Derek A. Paley , Senior Member, IEEE
Abstract—This paper describes the development of a self-
driving e-scooter with the ability to safely travel without a rider
along a pre-planned route using automated onboard control.
Ride-share electric scooters are an alternative to walking or
driving, but they are often ineffective or a nuisance due to
their placement after usage. An autonomous driving framework
specific to an e-scooter, including path planning and state estima-
tion, enables short-distance repositioning and parking. This paper
describes the framework’s hardware and software components
along with design choices and pitfalls. We also present results of
real-world autonomous navigation, including the effectiveness of
our localization methods.
Index Terms—Autonomous electric scooter, robot localization,
robot navigation, intelligent micromobility.
I. INTRODUCTION
SHARED micromobility systems like e-scooters are envi-
sioned to be a vital part of urban mobility that promises
improvements over current modalities like cars and buses
for short travel distances [1]–[6]. Despite their promise of
sustainable, accessible, and equitable transportation, shared
electric scooters clutter city sidewalks and landscapes. This
public nuisance causes city planners to limit the number of
shared operators and the size of their scooter fleets, which
in turn reduces revenue and diminishes the potential benefits
of dockless scooters. Further, to rent a shared scooter, a user
must find one nearby and walk to it. Rides must also end
in designated parking spots that may not be near the desired
destination [7]–[9].
There are large daily operating expenses with the recharging
and rebalancing of conventional scooters using cars and vans.
Not only is rebalancing expensive, but it may undo much of
the environmental benefit of shared electric scooters [10]. An
autonomous electric scooter could reposition itself for rider
convenience [11] and batch pickups. Even self-driving trips of
100-200m may increase the number of rides per day; e.g.,
consider re-positioning from the departure side of a train
station to the arrival side. Findings from the recent work of
Kondor et al., 2022 [12], indicate that self-repositioning capa-
bilities in scooters can significantly enhance vehicle utilization,
achieving up to ten times higher efficiency compared to current
This work is supported by the Maryland Robotics Center and a 2023
University of Maryland Grand Challenges Individual Project Grant
Srijal Shekhar Poojari is with the Department of Electrical and Com-
puter Engineering, University of Maryland, College Park, MD 20742, USA.
srijal@umd.edu
Jaxon Lee is with the Department of Computer Science, University of
Maryland, College Park, MD 20742, USA.
Derek A. Paley is with the Department of Aerospace Engineering and the
Institute for Systems Research, University of Maryland, College Park, MD
20742, USA.
Fig. 1. The three autonomous scooters developed: (L–R) Ben Parker, Richard
Parker, and Peter Parker
ride-share systems. To this end, algorithms and strategies have
been developed in simulation for repositioning micromobility
vehicles [12]–[14]. Our work develops the hardware and
software required to execute such repositioning for electric
scooters autonomously in the real world.
From a technology standpoint, a majority of the research in
self-driving technology is performed on robots that are larger
in size than electric scooters, i.e., predominantly self-driving
cars. Self-driving electric scooters present a novel challenge
because of their small form factor, small battery capacity, and
low unit costs. An autonomous e-scooter is required to travel
along roads, follow traffic signs, and avoid pedestrians, just
like an autonomous car. However, there is a gap in existing
knowledge about how to meet these needs when constrained
by size, weight, and power.
Previous research on autonomous electric scooters includes
[15], [16], which present a real-world implementation of a
self-stabilized scooter using a reaction wheel and methods
for autonomous navigation in simulation. Although we use
support wheels to stabilize the scooter, we have achieved
successful autonomous missions of over 375 meters in a
campus environment.
Other related research on autonomous mobility scooters
appears in [17]–[19]. These mobility scooters operate over
2
TABLE I
THE UNIVERSITY OF MA RYLA ND AUTONOMOUS SCO OTE R TEST BE DS
Scooter ver. 1: Ben Parker ver. 2: Richard Parker ver. 3: Peter Parker
OEM Platform Hover-1 Switch Mi M365 Hiboy S2
Stabilizing Mechanism Naturally stabilized Rigid support wheels Flexible supports with suspension
Camera Placement Handlebar Fixed to base Fixed to base
Camera(s) Used Intel RealSense T265 and D435i Stereolabs ZED2i Stereolabs ZED 2i
Compute Nvidia Jetson Nano Nvidia Jetson Nano/Orin Nvidia Jetson Orin
Is user rideable? No, small and unstable No, deck not clear Yes
similar routes and distances as electric scooters, but the larger
size allows for a larger onboard payload. The approach of
[17]–[19] does not rely on a Global Positioning System
(GPS) but rather Light Detection and Ranging (LiDAR) and
stereo cameras for Simultaneous Localization and Mapping
(SLAM). A LiDAR with SLAM is better suited for an urban
environment as compared to GPS alone, but adding LiDAR
increases unit cost and weight. For our scooter, we have chosen
to include only sensors (GPS, IMU and a stereo camera) that
can be scaled down in the future to be used with inexpensive
ride-share electric scooters.
Outside academia, Go X has deployed their self-driving
electric scooter fleet in 2020–21 as reported by news outlets
[20]. Go X Apollo scooters use retractable support wheels,
a friction drive mechanism at the front wheel and a camera
mounted at the top of the handlebars. The level of autonomy
achieved by these scooters is not known and no recent infor-
mation on their scooters is available online.
There has also been some work in developing autonomous
bicycle-sharing systems [21]–[25]. Bicycles closely parallel
electric scooters in function and application within urban
micromobility and therefore pose similar challenges for adding
autonomy. Most notably, the MIT Autonomous Bicycle Project
[22]–[25] is targeted towards shared bicycle systems and
presents an interesting hardware prototype. The bicycle has
a rear wheel that splits into a tricycle configuration for
stability without a rider. Their work analyzes the performance,
feasibility and sustainability of deploying autonomous shared
bicycles, but their prototype is not yet autonomous. We believe
that our proposed method of equipping autonomy to electric
scooters could be valuable for autonomous bicycles as well.
Our scooters have a single-board computer that performs
all onboard computing and runs the Robot Operating System
(ROS) on Ubuntu Linux. Additionally, we have a stereo
camera for depth sensing, an IMU, a GPS module, a motor
driver, and accompanying power circuitry. A unique aspect
of our approach is the use of past scooter ride data for
path planning. Historical scooter ride data from rental electric
scooters allows the scooter to take advantage of previous rides
performed by humans and learn the optimal paths to navigate
through the urban landscape.
The contributions of this paper are as follows: (1) the
application of robotics to electric scooters and a hardware
setup for making them autonomous; (2) the use of optimized
routing using historical data from manually operated rides to
create efficient route plans for a micromobility platform; and
(3) experimental results that validate the effectiveness of our
proof-of-concept platform in a university campus environment.
Fig. 2. An overview of the scooter’s components and physical configuration.
The image is of the version 3 prototype Peter Parker, which is user rideable.
This work seeks to create a low-emissions, convenient, and
accessible transportation modality for dense urban settings.
The outline of the paper is as follows. Section II describes
the autonomous scooter setup, including the mechanical and
electrical design. Section III describes the autonomy software
stack, including the scooter’s localization, planning and navi-
gation modules. Section IV presents experimental results for
localization and autonomous navigation. Section V summa-
rizes the paper along with ongoing and future work.
II. AUTONOMOUS SCOOTE R EXP ER IM EN TAL TES TB ED
An example of our retrofitted autonomous scooter is shown
in Figure 2, with the key elements labelled. Three such
scooters have been developed so far: Ben Parker, Richard
Parker, and Peter Parker. Each scooter improves upon the pre-
vious in mechanical design, component choice, and autonomy
capabilities, as summarized in Table I.
Two motors are required to control the scooter’s velocity
and steering angle. The drive motor is a brushless DC motor
included with the scooter. For steering, we use 3D printed
structures along with a belt and pulley mechanism, driven
by another brushless DC motor. Both motors are controlled
by an ODrive V3.6 motor driver, which replaces the Original
Equipment Manufacturer (OEM) driver and controller board.
Unlike [16], our scooters cannot self-stabilize, so support
wheels are added. The version 3 scooter’s support wheels
include a suspension system, allowing for tilt that dramatically
improves ride quality and stability.
On our first scooter, the stereo camera was placed on top of
the handlebar, making the camera turn as the handlebar turns.
3
Fig. 3. The scooter’s electrical components and connections
This was detrimental to autonomy performance, as we noticed
that with quick movements of the handlebar the camera would
lose tracking. We then decided to move the camera to the base
of the scooter in our subsequent designs.
An Nvidia Jetson AGX Orin is used as the onboard com-
puter that runs all autonomy software on Ubuntu with ROS.
Admittedly, this choice is expensive, significantly elevating our
prototype unit cost. However, we intend to create a functional
solution first and scale down on costs later. The overall
connection diagram is shown in Figure 3. All components are
powered from a lithium battery pack included with the OEM
scooter.
Since the OEM scooter controller has been removed, the
throttle and brake inputs must be rewired through the ODrive
for manual operation of the scooter. A Teensy microcontroller
has been added to read these inputs and send them to the
ODrive. As shown in Figure 3, commands from the Teensy
(manual) and Jetson (autonomy) are multiplexed and the
Teensy decides which input stream takes precedence. This
ensures that manual inputs override the autonomy inputs to
ensure rider safety at all times even if the Jetson is powered
off.
III. AUTONOMY SOFTWARE STACK
An overview of the scooter’s autonomy software stack is
shown in Figure 4. The objective is for the scooter to follow
a feasible path through a combination of roads, trails, and
sidewalk (if permitted) to reach and park in a designated
parking space. However, there are several problems here—
such as navigating from a raised sidewalk down to a crosswalk
[26]–[29] or carefully parking between other scooters or bikes
[30]–[32]—that are separate research challenges. Therefore,
Fig. 4. The scooter’s autonomy software stack
as a first proof-of-concept demonstration, we simplify the
navigation task in this paper as described in the subsequent
subsections.
A. Localization
We use an Extended Kalman Filter (EKF) from the robot lo-
calization package [33] for localization, fusing measurements
from an IMU, wheel encoders, and a GPS module. This ROS
package also includes a node to convert GPS measurements
from latitude/longitude to Cartesian coordinates in an earth-
fixed frame of our choice.
We have a camera onboard, but we do not use visual
odometry because of two issues: (1) poor tracking when the
environment is not feature-rich; and (2) self-shadowing, i.e.,
when the robot’s shadow falls into the camera field of view
and the robot sees its own shadow as a static feature on the
ground. Because of the scooter’s tall handlebar, this is an
issue during most hours of the day. Further, the covariance
reported by the camera in these degraded environments did not
reflect its inaccuracy and our EKF performed better without
visual odometry. Methods exist in literature to mitigate both
of these issues [34], but they have not yet been explored in
our research.
We assume that the scooter operates in a planar environment
and therefore configure the EKF in 2D mode, forcing roll,
pitch, and z(height) to zero. Following ROS Enhancement
Protocol, REP-105 [35], we use the map-odom-base co-
ordinate frame setup. This is done to combine benefits from
the sporadic but long-term stable GPS measurements with the
smooth, continuous updates from odometry sensors like IMUs
and wheel encoders that may drift over time. To get each of
the transformations, i.e., map-odom and odom-base, we
use two independent instances of the EKF, which are referred
to as the global EKF and local EKF, respectively. In our
present setup, the only difference between the two is that
the global EKF includes measurements from a GPS sensor,
whereas the local EKF does not. This ensures that the local
EKF remains continuous for near-distance obstacle avoidance
and path-planning without the sudden jumps that could be
caused when including intermittent fixes from GPS.
Since the EKF is not guaranteed to converge, we seek to
ensure that it is initialized as close as possible to the scooter’s
true state. An approximate initial position can be determined
4
Fig. 5. An illustration of the initialization procedure. Representative coordi-
nate frames are drawn for map (at the bottom) and base (on the scooter).
The camera–tag pose (yellow) is observed and the base–camera and map–
tag poses (purple) are known. We then compute the map–base transformation
(orange), which is the initial position of the scooter in this setup.
from GPS sensor readings before starting the EKF, but this
position is not reliable as the scooter may start near the edge
of building, which reduces the quality of GPS measurements.
Further, another challenge is knowing the initial heading with
hard and soft iron distortions from the motors, battery, scooter
chassis, and urban structures such as bike racks. Having a
pre-mapped database of the city is a possible solution, but as
a simpler alternative, we use AprilTags [36], [37] placed at
known global poses as reference anchors for initialization and
parking.
Figure 5 shows the basic initialization problem. The position
and orientation of the AprilTag in the world is known by
placing it on a clear, observable structure on Google Maps.
The map frame is assumed to be fixed at a some desired
world coordinate, say at the bottom left position, as shown
in the figure. The goal is to compute the position of the
scooter (orange) using known information (position of the
tag and base–camera transformation, purple) and observed
information (camera–tag pose, yellow). With yTxrepresenting
a transformation from frame xto frame y, this operation can
be performed using properties of a rigid transformation matrix,
i.e.,
[MTB]=[MTT][TTC][CTB],(1)
which implies
[MTB]=[MTT][CTT]−1[BTC]−1,(2)
where M,B,T, and Care the initials of frames map,base,
tag, and camera, respectively. Each transformation on the
right hand-side is either known or observed.
When a tag is placed at a fixed location outdoors, two
quantities are associated with it: (1) the latitude, longitude, and
heading of the tag is known and thus the transformation [UTT]
from the local Universal Transverse Mercator (UTM) frame;
and (2) the latitude, longitude, and heading of the desired map
frame location to be set, either at the scooter’s initial global
co-coordinates or any other fixed co-ordinate of choice. With
Fig. 6. A route generated by the cycling mode of Google Maps suggests a
path over some stairs. This would be an unsafe path for a self-driving scooter
and we propose using historical ride data from human-operated scooters to
generate better routes.
this information, we calculate the initial pose of the robot in
map, which is the initial state of global EKF, using
[MTB]=[UTM]−1[UTT][BTT]−1.(3)
Once state estimation is initialized, the scooter proceeds with
the mission.
B. Global Path Planning using Historical Ride Data
Widely available map databases such as OpenStreetMap
[38] or Google Maps are typically used for global path plan-
ning [5]. However, they provide insufficient information about
terrain, structures, sidewalks, or trails and may generate routes
that are unusable by an autonomous scooter. An example of
this can be seen in Figure 6, where the requested path for a
bicycle on Google Maps takes us over some stairs.
We use historical ride data from human-operated scooters
for global path planning, based on a two-month dataset from a
Veo scooter pilot at our campus in 2018 and 2019. This dataset
contains GPS coordinates of ride-share scooters logged every
6–8 seconds for over 14,468 trips.
To cluster and filter out this data, we used Uber H3, a
Hexagonal Hierarchical Spatial Index [39]. As seen in Figure
7, this graph contains vertices representing the hexes and undi-
rected edges representing instances of two hexes appearing
consecutively in a given trip. We used undirected edges to
maximize the frequency discount for edges in the graph, i.e.,
to allow the algorithm to better choose frequently traveled
edges. This choice was made with the assumption that most
routes will encounter the same obstacles when traveling in
either direction and thus the optimal path is similar in either
direction. A* is used for planning over this graph and, by
weighting our planning based on what routes human riders
have taken in the past, we generate a series of waypoints
that allow the scooter to autonomously navigate to a target
destination using an efficient and reasonable route.
We slightly modify the usual A* edge-weighing with a
discount factor to encode which edges were traveled more
5
Fig. 7. A sample route generated between start and end hexes (blue) overlaid
on a map of our campus. All recorded GPS locations in the datasets are
localized to hexes, and the darker hexes represent more frequently travelled
paths by human riders. The red hexes serve as waypoints for the autonomous
scooter.
frequently in the human ride dataset. Mathematically, the cost
C(u, v)to move from vertex uto vertex vin our approach is
C(u, v)=(we)ln(f)d(u, v) + h(u, g)(4)
where we≤1is the user-defined discount factor on the edge
weights used to indicate the frequency with which each edge
was traveled; fis the number of times that edge is seen in
the dataset; d(u, v)is the distance between vertices uand v;
and h(u, g)is the straight-line distance between vertex uand
goal g, i.e., the heuristic.
Whenever an edge is traveled more frequently in the dataset,
fincreases and, therefore, (we)ln(f)decreases, thereby de-
creasing the effective cost of that edge. This will result in this
particular edge being favored by the A* algorithm. We use the
natural logarithm of fto ensure that the effective edge cost
(we)ln(f)d(u, v)decreases at a decreasing rate as fincreases
linearly; f= 1 corresponds to the unmodified A* cost. This
process generates the waypoints for our mission, as seen in
Figure 7.
Finally, a simple NavFn planner [40] is used as an additional
planner for each waypoint. Presently, the costmap for this
planner is a blank grid, so the path generated is always a
straight line. In the future, a previously saved map could
be used for avoiding obstacles that do not show up in the
historical dataset.
C. Local Path Planning
The global planner accepts a goal and plans paths toward
waypoints without considering obstacles that show up while
the scooter is moving. The global planner passes the global
plan to the local planner, which then creates a local plan
considering real-time information from the scooter’s sensors
to carefully plan around objects in the immediate vicinity of
the scooter. The local planner cost map is created using a
point cloud from the stereo camera and a height threshold.
Any points above this threshold are treated as obstacles by
the local planner, including any dynamic obstacles that show
up.
The local planner plans the fine movements for the scooter
considering its kinematic constraints, which follow the bicycle
kinematic model. We do not want the local planner to plan
paths that are impossible for the scooter to achieve, for
example, to move sideways or turn on the spot. Therefore, we
use the Time Elastic Band local planner [41], which creates
plans for car-like robots. We configure the scooter’s kinematic
limits, including parameters like wheelbase, minimum turning
radius, and the robot’s footprint, and the planner outputs the
required steering angle and throttle velocity.
At the end of the mission, for parking, careful movements
are required to park between any present bicycles or scooters.
This is another challenge in itself and, to simplify the problem,
we use AprilTags placed in front of parking spaces as refer-
ence. Similar to the EKF initialization procedure, these April-
Tags act as placeholders for an improved parking algorithm in
the future. As the scooter moves toward its final waypoint, we
search for the specific, pre-configured destination AprilTag.
Upon detection, the parking goal poses are generated at a
specified distance (about 1.5 meters) in front of the tag. A
multiplexer called Selective Goal Publisher recognizes that the
scooter is close to its destination and passes these parking
goals to the path planner instead of waypoints. The global
and local planner use these goals to park the scooter at the
required location. A parking goal’s position and orientation
tolerances may be smaller than a waypoint, ensuring well-
aligned parking.
IV. AUTONOMOUS DRIVING EXPERIMENTAL RES ULTS
This section presents the effectiveness of our localization
method and performance during autonomous missions over
different roads and trails. To evaluate localization, we man-
ually move the scooter on a set path, recording global EKF
output and comparing it against ground truth coordinates of
visually identifiable Google Maps features, such as manhole
covers, and noting the timing of the scooter’s passage. For
initializing the EKF, the scooter starts at a location facing a
known AprilTag as described in Section III. These tests were
repeated for more than 3 kilometers of travel in total; the
distance error from ground truth has a mean of 0.97 meters
and standard deviation of 0.67 meters.
During autonomous motion, it is difficult to get ground truth
for the path that the scooter takes. We can only qualitatively
evaluate how well the scooter follows a route by plotting
the shortest distance from each waypoint to the global EKF
curve. But since the waypoint publisher switches to the next
waypoint as soon as the scooter is within 3 meters of the
current waypoint, we cannot expect this distance to be zero.
Figure 8 and 9 show the scooter’s position reported by the
global EKF and the given waypoints for autonomous missions
over routes of length 400 and 375 meters, respectively. No
human intervention is required throughout these missions.
Figure 10 shows the shortest distance from the scooter’s
estimated position to the nearest waypoint for three different
autonomous missions. Linear regression is performed on each
6
Fig. 8. The plot shows results of the scooter moving autonomously between the given waypoints for a path length of about 400 meters. Waypoints are marked
in red and the yellow curve shows the output of the global EKF, which is the scooter’s estimated position in the map frame. The distances from the EKF
global curve to each waypoint is plotted in Figure 10 with the label Mission 2. Note how the scooter successfully travels along the trail on the right but
localization suffers as GPS deteriorates near the vicinity of a tall building, leading to an error of about 2 meters at the final waypoint. However, the AprilTag
placed at the parking location helps the scooter successfully park itself.
Fig. 9. The plot shows results of the scooter moving autonomously between the given waypoints for a path length of 375 meters. Waypoints are marked in
red and the yellow curve shows the output of the global EKF, which is the scooter’s estimated position in the map frame. The distances from the EKF global
curve to each waypoint is plotted in Figure 10 with the label Mission 3.
7
Fig. 10. Distance error from ground truth vs. distance travelled by the scooter
in meters. Linear regression is performed for each run to show that distance
error is not increasing over each mission.
test set to show that the trend in distance from waypoint does
not increase substantially with distance traveled. The mean
and standard deviation of this distance for these three missions
combined were 0.64 meters and 0.61 meters, respectively. The
worst-case observed distance from a waypoint reached 3.07
meters while executing a sharp, 90-degree turn during Mission
1. Also note that both Mission 1 and Mission 2 end in parking
spaces next to tall buildings. Hence, a higher distance from
waypoint of about 2 meters is observed toward the end of
those missions.
This performance is acceptable for travelling along wide
roads but not necessarily for narrow paths or sidewalks. In
one particular test, the scooter approached a split road and the
error in state estimation caused it to think that the waypoint
was on the left instead of the right side. This caused the scooter
to proceed down the wrong way and, eventually, it could not
make it to the other side and the mission failed. In another
test, as the scooter moved too close to a building (Figure 11),
GPS reported false readings and the scooter could not localize
itself correctly. The mission ended about 4 meters away from
the given waypoint in this case. This is expected when relying
on GPS in an urban environment, and is on par with similar
implementations in literature [42].
Overall, the proposed autonomy stack is capable of driving
the scooter from a given start and end location along roads and
trails when the following conditions are met: (1) the scooter
maintains some distance from tall urban structures and GPS
is not significantly deteriorated, (2) AprilTags are placed at
these start and end locations for accurate initialization and
parking, and (3) any obstacles to be avoided are above the pre-
determined height threshold. Ongoing and future work seek to
improve performance and relax these constraints.
V. CONCLUSION
This paper presents the development process and design
decisions taken to implement an autonomous electric scooter,
starting from off-the-shelf scooter hardware. The localization
and navigation framework for the scooter is presented, along
with results demonstrating its success along campus roads.
While previous research on autonomous scooters has focused
Fig. 11. Image shows error developed in state estimate when the scooter
is moved through a narrow path between two buildings. Erroneous GPS
measurements (green) cause the estimate (yellow) to shift along with it. The
red arrow shows ground truth path.
primarily on simulations or self-stabilizing methods, our work
presents a comprehensive hardware and software framework
that enables fully autonomous navigation and parking in a
complex urban environment. However, without the use of
visual guidance, localization performance suffers when the
GPS is erroneous. The effect of this is seen during autonomous
navigation and the scooter requires a sufficiently wide path
for travel. A different extension of the Kalman filter could
potentially enhance performance in such scenarios [43], [44].
Furthermore, since obstacle avoidance is performed solely
using depth information from a stereo camera with a height
threshold, it cannot currently distinguish surfaces like sidewalk
and grass when they are nearly the same height. These are
widely known problems in autonomous navigation, and are
the focus of extensive ongoing research [45]–[48].
Ride-shared electric scooters are deployed within a rela-
tively known region such as university campuses and, there-
fore, it is reasonable to assume that a map of the region is
available. Hence, we are exploring SLAM-based algorithms
for improving localization. Further, we are also incorporating
image segmentation into our motion-planning pipeline. This
will compensate for any regions to be avoided in the immediate
vicinity of the robot by having segmented regions weigh in on
the local planner’s cost map.
Other challenges for ongoing and future research include de-
veloping improved localization that allows precise movements,
initialization, and parking without the use of fiducial markers,
and safe operation of the scooter in an urban environment with
pedestrians.
ACKNOWLEDGMENTS
This research is supported by the Maryland Robotics
Center and a 2023 University of Maryland Grand Chal-
lenges Individual Project Grant. The authors thank Raj
Shinde, Pruthvi Sanghvi, Naman Gupta, Andrew Giorgi, Sid-
dharth Telang, Jeremy Kuznetsov, Sharmitha Ganesan, Vibhu
Agrawal, Matthew Fedora, Neha Madhekar and Mudit Singal
for their contributions to the scooter research.
Note that the majority of work presented in this paper has
first appeared in the first author’s master’s thesis [49]; certain
8
figures have been updated, and the described method of global
path planning and parking appears here for the first time.
REFERENCES
[1] J. Lazarus, J. C. Pourquier, F. Feng, H. Hammel, and S. Shaheen,
“Micromobility evolution and expansion: Understanding how docked and
dockless bikesharing models complement and compete – A case study
of San Francisco,” Journal of Transport Geography, vol. 84, p. 102620,
Apr. 2020. DOI: 10.1016/j.jtrangeo.2019.102620
[2] L. Hawa, B. Cui, L. Sun, and A. El-Geneidy, “Scoot over: Determinants
of shared electric scooter presence in Washington D.C,” Case Studies
on Transport Policy, vol. 9, no. 2, pp. 418–430, Jun. 2021. DOI:
10.1016/j.cstp.2021.01.003
[3] S. Tuncer, E. Laurier, B. Brown, and C. Licoppe, “Notes on the
practices and appearances of e-scooter users in public space,” Jour-
nal of Transport Geography, vol. 85, p. 102702, May 2020. DOI:
10.1016/j.jtrangeo.2020.102702
[4] M. E. Moran, B. Laa, and G. Emberger, “Six scooter operators, six maps:
Spatial coverage and regulation of micromobility in Vienna, Austria,”
Case Studies on Transport Policy, vol. 8, no. 2, pp. 658–671, Jun. 2020.
DOI: 10.1016/j.cstp.2020.03.001
[5] R. Zhu, X. Zhang, D. Kondor, P. Santi, and C. Ratti, “Understanding
spatio-temporal heterogeneity of bike-sharing and scooter-sharing mobil-
ity,” Computers, Environment and Urban Systems, vol. 81, p. 101483,
May 2020. DOI: 10.1016/j.compenvurbsys.2020.101483
[6] Y. Feng et al., “Micromobility in Smart Cities: A Closer Look at
Shared Dockless E-Scooters via Big Social Data,” in IEEE Inter-
national Conference on Communications, Jun. 2021, pp. 1–6. DOI:
10.1109/ICC42927.2021.9500821
[7] S. G ¨
ossling, “Integrating e-scooters in urban transportation: Problems,
policies, and the prospect of system change,” Transportation Research
Part D: Transport and Environment, vol. 79, p. 102230, Feb. 2020. DOI:
10.1016/j.trd.2020.102230
[8] A. Brown, N. J. Klein, and C. Thigpen, “Can you Park your Scooter
There? Why Scooter Riders Mispark and What to do about it,” Findings,
Feb. 2021. DOI: 10.32866/001c.19537
[9] N. Klein, A. Brown, and C. Thigpen, “Clutter and Compliance: Scooter
Parking Interventions and Perceptions,” Active Travel Studies, vol. 3, no.
1, Art. no. 1, Jan. 2023. DOI: 10.16997/ats.1196
[10] B. Turan and T. Wakolbinger, “The Electric Scooter Collection Problem:
A Case Study in the City of Vienna,” Sustainability, vol. 15, no. 13, Art.
no. 13, Jan. 2023. DOI: 10.3390/su151310058
[11] T. Zou and D. MacKenzie, “Bike lanes and ability to summon an
autonomous scooter can increase willingness to use micromobility,”
Transportation, Apr. 2024. DOI: 10.1007/s11116-024-10478-5
[12] D. Kondor, X. Zhang, M. Meghjani, P. Santi, J. Zhao, and C. Ratti, “Es-
timating the Potential for Shared Autonomous Scooters,” IEEE Transac-
tions on Intelligent Transportation Systems, vol. 23, no. 5, pp. 4651–4662,
May 2022. DOI: 10.1109/TITS.2020.3047141
[13] N. Coretti Sanchez, I. Martinez, L. Alonso Pastor, and K. Larson,
“On the simulation of shared autonomous micro-mobility,” Communi-
cations in Transportation Research, vol. 2, p. 100065, Dec. 2022. DOI:
10.1016/j.commtr.2022.100065
[14] M. D. Dean, K. M. Gurumurthy, F. de Souza, J. Auld, and K. M.
Kockelman, “Synergies between repositioning and charging strategies for
shared autonomous electric vehicle fleets,” Transportation Research Part
D: Transport and Environment, vol. 108, p. 103314, Jul. 2022. DOI:
10.1016/j.trd.2022.103314
[15] P. Wenzelburger and F. Allgower, “A first step towards an autonomously
driving e-scooter,” in Proc. 21th IFAC World Congress, pp. 1–4. 2020.
[16] R. Soloperto, P. Wenzelburger, D. Meister, D. Scheuble, V. S. M.
Breidohr, and F. Allgower, “A control framework for autonomous e-
scooters,” in 16th IFAC Symposium on Control in Transportation Systems
2021, vol. 54, Jan. 2021, pp. 252–258. DOI: 10.1016/j.ifacol.2021.06.030
[17] H. Andersen et al., “Autonomous personal mobility scooter for multi-
class mobility-on-demand service,” in 2016 IEEE 19th International
Conference on Intelligent Transportation Systems, Nov. 2016, pp. 1753–
1760. DOI: 10.1109/ITSC.2016.7795795
[18] R. S. Mulky, S. Koganti, S. Shahi, and K. Liu, “Autonomous scooter
navigation for people with mobility challenges,” in 2018 IEEE Inter-
national Conference on Cognitive Computing, 2018, pp. 87–90. DOI:
10.1109/ICCC.2018.00020
[19] K. Liu and R. Mulky, “Enabling autonomous navigation for affordable
scooters,” Sensors, vol. 18, no. 6, p. 1829, 2018. DOI: 10.3390/s18061829
[20] K. Hyatt, “Go X is unleashing 100 self-driving scooters on a large Geor-
gia Business Park,” CNET, https://www.cnet.com/roadshow/news/go-x-
peachtree-corners-self-driving-scooter-test-fleet/ (accessed Oct. 31, 2023).
[21] I. Haj Salah, V. D. Mukku, M. Kania, T. Assmann, and H. Zadek, “Could
the next generation of bike-sharing with autonomous bikes be financially
sustainable?,” Journal of Urban Mobility, vol. 6, p. 100084, Dec. 2024.
DOI: 10.1016/j.urbmob.2024.100084
[22] N. C. Sanchez, L. A. Pastor, and K. Larson, “Can autonomy make
bicycle-sharing systems more sustainable? An environmental impact
analysis,” Transportation Research Part D: Transport and Environment,
vol. 113, p. 103489, Dec. 2022. DOI: 10.1016/j.trd.2022.103489
[23] N. C. Sanchez, I. Martinez, L. A. Pastor, and K. Larson, “On the
performance of shared autonomous bicycles: A simulation study,” Com-
munications in Transportation Research, vol. 2, p. 100066, Dec. 2022.
DOI: 10.1016/j.commtr.2022.100066
[24] N. C. Sanchez et al., “Urban Mobility Swarms: Towards a Decentral-
ized Autonomous Bicycle-Sharing System,” in 2023 IEEE 26th Interna-
tional Conference on Intelligent Transportation Systems, Sep. 2023, pp.
2323–2330. DOI: 10.1109/ITSC57777.2023.10421869
[25] N. C. Sanchez, L. A. Pastor, and K. Larson, “Autonomous Bicycles:
A New Approach To Bicycle-Sharing Systems,” in 2020 IEEE 23rd
International Conference on Intelligent Transportation Systems, Sep.
2020, pp. 1–6. DOI: 10.1109/ITSC45102.2020.9294332
[26] T. D. Trinh, T. P. Nguyen, T. N. D. Le, N. Van Nguyen, N. C.
Debnath, and V. D. Nguyen, “Robust Crosswalk Detection Using Deep
Learning Approach,” in Proceedings of the International Conference on
Advanced Intelligent Systems and Informatics 2021, 2022, pp. 62–69.
DOI: 10.1007/978-3-030-89701-7 6
[27] G. Do ˘
gan and B. Ergen, “A new hybrid mobile CNN approach for
crosswalk recognition in autonomous vehicles,” Multimedia Tools and
Applications, vol. 83, no. 26, pp. 67747–67762, Aug. 2024. DOI:
10.1007/s11042-024-18199-8
[28] D. Chugo, S. Yamada, S. Muramatsu, S. Yokota, J.-H. She, and H.
Hashimoto, “Mobile Robot Navigation Considering How to Move with
a Group of Pedestrians in a Crosswalk,” in 2021 14th International
Conference on Human System Interaction, Jul. 2021, pp. 1–7. DOI:
10.1109/HSI52170.2021.9538660
[29] S. K. Jayaraman, D. M. Tilbury, X. Jessie Yang, A. K. Pradhan, and L.
P. Robert, “Analysis and Prediction of Pedestrian Crosswalk Behavior
during Automated Vehicle Interactions,” in 2020 IEEE International
Conference on Robotics and Automation, May 2020, pp. 6426–6432.
DOI: 10.1109/ICRA40945.2020.9197347
[30] S. Alfasly, Z. Al-Huda, S. A. Bello, A. Elazab, J. Lu, and C. Xu, “OSRE:
Object-to-Spot Rotation Estimation for Bike Parking Assessment,” IEEE
Transactions on Intelligent Transportation Systems, vol. 25, no. 6, pp.
6013–6022, Jun. 2024. DOI: 10.1109/TITS.2023.3330786
[31] S. Xie, Y. Li, Q. Xu, F. Fang, and L. Li, “Image-based Parking Place
Identification for Regulating Shared Bicycle Parking,” in 2018 15th
International Conference on Control, Automation, Robotics and Vision,
Nov. 2018, pp. 1709–1714. DOI: 10.1109/ICARCV.2018.8581276
[32] S. Ma, H. Jiang, M. Han, J. Xie, and C. Li, “Research on Automatic
Parking Systems Based on Parking Scene Recognition,” IEEE Access,
vol. 5, pp. 21901–21917, 2017. DOI: 10.1109/ACCESS.2017.2760201
[33] T. Moore and D. Stouch, “A generalized extended Kalman filter im-
plementation for the robot operating system,” in Intelligent Autonomous
Systems 13: Proceedings of the 13th International Conference IAS-13,
Springer International Publishing, 2016, pp. 335–348. DOI: 10.1007/978-
3-319-08338-4 25
[34] N. Seegmiller and D. Wettergreen, “Optical flow odometry with ro-
bustness to self-shadowing,” in 2011 IEEE/RSJ International Confer-
ence on Intelligent Robots and Systems, 2011, pp. 613–618. DOI:
10.1109/IROS.2011.6094670
[35] W. Meeussen, “Coordinate frames for mobile platforms,” ros.org,
https://ros.org/reps/rep-0105.html (accessed Oct. 31, 2023).
[36] E. Olson, “AprilTag: A robust and flexible visual fiducial system,” in
2011 IEEE International Conference on Robotics and Automation, May
2011, pp. 3400–3407. DOI: 10.1109/ICRA.2011.5979561
[37] J. Wang and E. Olson, “AprilTag 2: Efficient and robust fidu-
cial detection,” in 2016 IEEE/RSJ International Conference on In-
telligent Robots and Systems, Oct. 2016, pp. 4193–4198. DOI:
10.1109/IROS.2016.7759617
[38] OpenStreetMap, https://www.openstreetmap.org/ (accessed Sep. 18,
2024).
[39] I. Brodsky, “H3: Uber’s Hexagonal Hierarchical Spatial Index,” Uber
Inc., https://www.uber.com/blog/h3/ (accessed Feb. 28, 2023).
[40] D. V. Lu, “NavFn: A fast, interpolated navigation function,” ros.org,
http://wiki.ros.org/navfn (accessed Nov. 1, 2023)
9
[41] C. Rosmann, F. Hoffmann, and T. Bertram, “Kinodynamic trajectory
optimization and control for car-like robots,” in 2017 IEEE/RSJ Inter-
national Conference on Intelligent Robots and Systems, Sep. 2017, pp.
5681–5686. DOI: 10.1109/IROS.2017.8206458
[42] A. Georgiev and P. K. Allen, “Localization methods for a mobile robot
in urban environments,” in IEEE Transactions on Robotics, vol. 20, no.
5, pp. 851-864, Oct. 2004. DOI: 10.1109/TRO.2004.829506
[43] C. Urrea and R. Agramonte, “Kalman Filter: Historical Overview and
Review of Its Use in Robotics 60 Years after Its Creation,” Journal of Sen-
sors, vol. 2021, no. 1, p. 9674015, Jan. 2021. DOI: 10.1155/2021/9674015
[44] P. K. Panigrahi and S. K. Bisoy, “Localization strategies for autonomous
mobile robots: A review,” Journal of King Saud University - Computer
and Information Sciences, vol. 34, no. 8, Part B, pp. 6019–6039, Sep.
2022. DOI: 10.1016/j.jksuci.2021.02.015
[45] K. Muhammad et al., “Vision-Based Semantic Segmentation in Scene
Understanding for Autonomous Driving: Recent Achievements, Chal-
lenges, and Outlooks,” in IEEE Transactions on Intelligent Transporta-
tion Systems, vol. 23, no. 12, pp. 22694-22715, Dec. 2022. DOI:
10.1109/TITS.2022.3207665
[46] D. Feng et al., “Deep Multi-Modal Object Detection and Semantic Seg-
mentation for Autonomous Driving: Datasets, Methods, and Challenges,”
in IEEE Transactions on Intelligent Transportation Systems, vol. 22, no.
3, pp. 1341-1360, Mar. 2021. DOI: 10.1109/TITS.2020.2972974
[47] I. Abaspur Kazerouni, L. Fitzgerald, G. Dooly, and D. Toal, “A survey
of state-of-the-art on visual SLAM,” Expert Systems with Applications,
vol. 205, p. 117734, Nov. 2022. DOI: 10.1016/j.eswa.2022.117734
[48] J. Cheng, L. Zhang, Q. Chen, X. Hu, and J. Cai, “A review of
visual SLAM methods for autonomous driving vehicles,” Engineering
Applications of Artificial Intelligence, vol. 114, p. 104992, Sep. 2022.
DOI: 10.1016/j.engappai.2022.104992
[49] S. S. Poojari, “Outdoor localization and path planning for repositioning
a self-driving electric scooter,” M.S. thesis, University of Maryland, 2023.
DOI: 10.13016/dspace/tbvg-9is5.
Srijal Shekhar Poojari (Member, IEEE) received
the B.E. degree in Electronics Engineering from
the University of Mumbai, India in 2019 and M.S.
degree in Systems Engineering from the University
of Maryland, College Park, MD, USA, in 2023.
He is currently working toward the Ph.D. degree in
Electrical and Computer Engineering the University
of Maryland. From 2019 to 2020, he was a Research
Associate at the Sardar Patel Institute of Technology,
Mumbai, working on embedded systems and power
electronics. Since 2021, he is a Research Assistant
at the Institute for Systems Research, University of Maryland. His research
interests include field robotics, applied control systems and embedded sys-
tems.
Jaxon Lee received the B.S. degree in Computer
Science from the University of Maryland, College
Park, USA, in 2024. From 2022 to 2024, he was
an Undergraduate Researcher with the Maryland
Robotics Center working on the autonomous scooter
project. His research interests include robotics and
AI.
Derek A. Paley (Senior Member, IEEE) received the
B.S. degree in applied physics from Yale University
in 1997 and the Ph.D. degree in mechanical and
aerospace engineering from Princeton University in
2007. He is currently the Director of the Maryland
Robotics Center and the Willis H. Young, Jr., Profes-
sor of Aerospace Engineering Education in the De-
partment of Aerospace Engineering and the Institute
for Systems Research, University of Maryland. He
teaches introductory dynamics, advanced dynamics,
aircraft flight dynamics and control, and nonlinear
control. His research interests are in the area of dynamics and control,
including cooperative control of autonomous vehicles, adaptive sampling
with mobile networks, spatial modeling of biological groups, and bioinspired
robotics. He serves as an Associate Editor for the Journal of Guidance,
Control, and Dynamics (AIAA) and IEEE Control Systems Magazine.