ORIGINAL RESEARCH article

Improving autonomous robotic navigation using imitation learning.

Brian Csar-Tondreau,

  • 1 Unmanned Systems Laboratory, Mechanical Engineering, Virginia Polytechnic Institute and State University, Blacksburg, VA, United States
  • 2 Army Research Laboratory, Adelphi, MD, United States

Autonomous navigation to a specified waypoint is traditionally accomplished with a layered stack of global path planning and local motion planning modules that generate feasible and obstacle-free trajectories. While these modules can be modified to meet task-specific constraints and user preferences, current modification procedures require substantial effort on the part of an expert roboticist with a great deal of technical training. In this paper, we simplify this process by inserting a Machine Learning module between the global path planning and local motion planning modules of an off-the shelf navigation stack. This model can be trained with human demonstrations of the preferred navigation behavior, using a training procedure based on Behavioral Cloning, allowing for an intuitive modification of the navigation policy by non-technical users to suit task-specific constraints. We find that our approach can successfully adapt a robot’s navigation behavior to become more like that of a demonstrator. Moreover, for a fixed amount of demonstration data, we find that the proposed technique compares favorably to recent baselines with respect to both navigation success rate and trajectory similarity to the demonstrator.

1 Introduction

Decades of work in autonomous robot navigation have resulted in a well-studied and successful framework for safe and efficient traversal in known and unknown environments. Given an accurate environment map, autonomous navigation can be accomplished with a combination of global path planning ( Kavraki et al., 1996 ; LaValle and Kuffner Jr, 2001 ) and local motion control ( Petrovic, 2018 ; Thrun, 1998 ). Valid trajectories are typically computed by optimizing a pre-specified cost function that measures factors such as path length, chance of collision, and execution time ( Petrovic, 2018 ).

However, adapting this standard framework to exhibit unanticipated but necessary navigation behaviors can be challenging. The need for such adaptation arises because what constitutes a valid trajectory can vary across users, tasks, and the specific environments in which the agent is deployed. For example, in situations such as disaster robotics ( Doroodgar et al., 2014 ; Liu et al., 2012 ), the ability to perform on-the-fly adaption of navigation behaviors in light of new information in dynamic environmental conditions (e.g., decreased traversability of roads due to partial flooding), may prove critical to the success of the mission. Explicitly modifying the navigation cost function to induce valid trajectories may be possible, but doing so accurately and quickly currently requires substantial effort from an expert roboticist with a great deal of technical training, if it can be done at all. Therefore, we seek alternate methods for incorporating user preferences into autonomous navigation systems that do not involve explicitly re-writing computer code or specifying cost functions and are accessible to users without training in robotics. Combining autonomous navigation with Machine Learning is a promising approach by which such alternate methods might be developed. In particular, Learning from Demonstration (LfD) ( Argall et al., 2009 )—in which a machine learner attempts to imitate the behavior of a demonstrator—is directly applicable to the problem of autonomous navigation since many humans can successfully provide demonstrations by tele-operating the platform. Unfortunately, precisely how LfD approaches should be applied to the problem of autonomous navigation still remains unclear. Existing approaches based on Inverse Reinforcement Learning ( Wigness et al., 2018 ) may incur large training costs, and approaches based on Behavioral Cloning (BC) ( Bojarski et al., 2016 ) are limited by common issues such as data distribution shift ( Ross et al., 2010 ) and lack of generalization. Furthermore, many existing approaches incur a prohibitively large human cost in terms of amount of demonstration data required ( Neu and Szepesvári, 2012 ; Pfeiffer et al., 2018 ).

In this paper, we propose a new framework for combining autonomous navigation and LfD to overcome these limitations. The key idea is to combat the costs inherent in pure Machine Learning approaches by leveraging an appropriate amount of the existing machinery of planning and control. This idea has been successfully used in other contexts in the form of a learned navigation system that can propose intermediate waypoints ( Bansal et al., 2019 ) or approximate planner costs that have no easy calculation ( Stein et al., 2018 ). Such hybrid approaches leverage the results and guarantees of decades of work in optimal control and planning but take advantage of specific locations where heuristics can speed up or shape the results.

Our proposed approach adopts such a hybrid approach in the context of LfD in two novel ways: 1) by integrating BC directly into an off-the-shelf navigation stack through a module we insert between the existing global path planner and the local motion planner, and 2) by using a training paradigm that uses demonstrations from both humans and a classical navigation stack to increase the overall system success rate. With respect to (1) in particular, the inserted module takes input from both the platform’s on-board sensors and the global path planner to produce intermediate goals for the local planner. Unlike traditional systems in which these intermediate goals are specified by the global planner, the goals produced by our module are the output of a learned function that is trained to emulate navigation behavior as demonstrated through tele-operation by a human. We study the proposed method experimentally in a simulated environment. Specifically, for a fixed amount of demonstration data, we seek to characterize the efficacy of our approach in terms of both the similarity of the produced navigation trajectories to that of the demonstrator as well as the overall navigation task success rate. We evaluate the performance of our proposed method in two simulation environments: 1) a simple proof of concept environment simulated in Gazebo ( Koenig and Howard, 2004 ), and 2) a more realistic and complex environment simulated in Unity ( Unity Technologies ). We compare our technique to recently-proposed baselines that also propose to incorporate LfD with autonomous navigation, and we find that the proposed technique excels in performance.

2 Related Work

In this section, we discuss classical approaches for robotic navigation, followed by a brief exploration of Machine Learning from Demonstration, then conclude this section by highlighting recent hybrid approaches that try to combine the two.

Classical robot navigation is accomplished with a hierarchical suite of navigation software. Specifically, a global path planning module that generates optimal paths given an occupancy map, and local planner that executes feasible control signals that adhere to the robot’s kinematic constraints and a mathematically defined objective function ( Kalakrishnan et al., 2011 ; Kavraki et al., 1996 ; Laumond et al., 1994 ; LaValle and Kuffner Jr, 2001 ). While this setup can reliably generate geometrically optimal trajectories and motions over long distances, navigation trajectories/behaviors that are optimal with respect to user preferences or constraints are not easily defined mathematically. Thus, necessitating inclusion of Machine Learning approaches to traditional path planning.

Recent interest in improving upon traditional robot navigation have been geared towards leveraging Machine Learning techniques such as Learning from Demonstration (LfD) to help facilitate robot navigation. Learning from Demonstrations can be decomposed into two general areas based on the approach: Behavioral Cloning (BC), an application of Supervised Learning where a mapping from observations to actions is learned ( Ross et al., 2010 ) and Inverse Reinforcement Learning (IRL), which generates a reward function that explains the demonstrated behavior ( Abbeel et al., 2004 ; Ziebart et al., 2008 ). Some approaches attempt to use Machine Learning in isolation for handling robot navigation. For example, Chiang et al. frame the navigation task as an end-to-end learning problem to predict continuous controls (e.g., steering angle, translational and rotational velocities) directly from raw state observations ( Lewis Chiang et al., 2018 ).

Other recent works attempt to combine Machine Learning and classical navigation as an intuitive means to quickly model preferences for a navigation task with the help of a human teacher. Wigness et al. (2018) and Siva et al. (2019) , combine IRL and visual feature extraction to train navigation policies in unstructured terrains from human demonstrations. However, methods for IRL involve an iterative constrained search through the space of reward functions, leading to a disproportionate growth in solution complexity with the problem size. Müller et al. (2018) aim to transfer driving policies from simulation to physical platforms and achieve this by learning policies that output a series of waypoints to be followed by a lower-level planning and control system. They focused on a general navigation task rather than consideration of how this setup might be used as a mechanism for Imitation Learning. Gao et al.’s intention-net ( Gao et al., 2017 ), and Pokle et al.’s work ( Pokle et al., 2019 ) are similar to our own approach as they utilize the global planner provide the general direction that a robot should travel to reach a desired destination in a known environment. These methods attempt to address the shortcomings of classical navigation with Machine Learning at the cost of high training time, complexity, and data efficiency by training models to replace the functionality of proven low level controllers used in classical navigation techniques. Instead of replacing the local controller, our approach integrates a trained policy as an intermediate module between the path planner and local controller modules found in any off-the shelf navigation software. This effectively combines an intuitive interface for a human user to adapt a proven, but inflexible, navigation control scheme with their own preferences and behavior on how the navigation problem should be solved.

Our key contributions are twofold. First, we introduce a novel and efficient training scheme for using LfD in autonomous navigation that contrasts with current-state of the art approaches. Second, we provide empirical evidence that our new that the proposed method can achieve high path completion rates in both familiar training and novel testing environments while adhering to an implicitly defined navigation rule embedded in human demonstration.

Our proposed approach integrates a behavior cloning model directly into an off-the-shelf navigation stack as a means to enable adaptation via human-demonstrated navigation behaviors. Figure 1 shows a system diagram of the proposed architecture, wherein our behavior cloning model takes as input the current bearing to the global goal and a windowed sequence of sensory and state estimation information, and provides as output a local goal for the local planner. In this section we provide a general overview of the proposed system architecture, followed by our model training and demonstration collection procedure.

www.frontiersin.org

FIGURE 1 . (A) Proposed execution pipeline for improved autonomous navigation: a neural network is inserted before the local planner in the default ROS navigation stack. This network is trained using BC from human demonstrations to map current state and task information to goals for the local planner. (B) Visualization of image features, lidar data, distance to goal, and relative bearing to goal features are collected and transformed to low dimensional inputs to the policy model. (C) The Imitation Learning module that maps the observations of the current state, pre-processed in the feature extraction step, to a local goal for the local planner.

3.1 State Space and Feature Extraction

We modify a traditional layered navigation stack of global and local path planning modules by inserting between them a new Machine Learning module. This module accepts as input both platform sensor data as well as features related to the global planner, and outputs goals for the local planner. Below, we describe the state and action spaces for our Machine Learning module in more detail.

The feature extraction and compilation process we use is detailed in Figure 1B . The features include perceptual observations of the current state (i.e., visual cues extracted from images or spatial information from a planar lidar) and task information in the form of the current distance and relative bearing to the navigation goal. As a means by which to supply the imitation learner with historical context, we also employ a temporal stacking technique for each of the above features. In our work, as shown in Figure 1B , we stack m = 2 sequential (current and previous time instant) features. For the perceptual observations f c and f l , this amounts to moving from size 72 × 1 each to 2 × 72 × 1 each. For the task features, f B goes from 1 × 20 to 1 × 40 and f D from a scalar to 1 × 2 . The state space, s t ∈ S , is a low dimensional representation of the free space in the environment, and is comprised of the following features:

Lidar features: The lidar feature vector, f l , consists of n evenly sampled laser range points from a 360° planar lidar. Here, n = 72 , which corresponds to a lidar measurement sampled every 5° (see Figure 1B ).

Visual features: The visual feature vector, f C , is processed from a panoramic RGB image of the robot’s surroundings that underwent pixel level semantic labelling of the objects in its visual frame. Specifically, the panoramic RGB image can be generated by a camera with a 360° horizontal field of view, or several cameras arranged about the robot chassis to produce a similar image. From the RGB image(s), we generate a pixel level semantic image, labeling each object type (e.g., crate, building, gravel, etc) in the image frame with a unique color (see Figure 3F ). While our simulator directly generates these semantically labeled images, in real world environments, one can acquire similar ones using deep networks for classification and image segmentation such as Mask RCNN ( He et al., 2017 ) or DeepLabv3 ( Chen et al., 2017 ). Each element in f C indicates the presence of an object of interest (such as color, texture, or pattern) within a segment of the camera’s horizontal field of view (HFOV) (see Figures 1B , 3E ).

Goal bearing feature: The goal bearing feature, f B , provides our network with the navigation goal location’s relative bearing to the robot at time t . It serves to orient the model’s predicted actions in the direction of the goal even when maneuvers to avoid obstacles or adhere to human navigation preferences leave the robot facing opposite to the goal location (see Figure 1B ).

Distance feature: f D is the euclidean distance between the robot and the desired goal location at time t . We use distance to the goal to avoid training the BC model to navigate to specific goal locations used in training. This allows the policy to generalize its behavior to goal locations not seen during training (see Figure 1B ).

3.2 Action Space

As discussed in Section 2, most methods combining Machine Learning with classical navigation, train a model that directly predicts low level control signals from raw sensory data, effectively replacing the local planner. Our model, however, takes advantage of the local motion planning module included in the ROS navigation stack. To do so, our model predicts one of L = 9 class labels, each of which corresponds to a 2D waypoint A = { a l | l = 0 , … , L − 1 } . Each waypoint was sampled at predefined angular intervals along the arc of a semicircle in front the robot in its coordinate frame of reference (see Figure 2A ). Given the current observation of the state, s t , our BC model outputs L scores—one for each predefined waypoint—and the waypoint with the highest score is then passed to the local planner. This leaves the computation of valid low-level control signals to the local planner which is specifically designed to consider the kinematic constraints of the robot platform in its plan. Over the course of the model’s execution, the model’s predicted waypoints should result in a path that adheres to the demonstrated user preferences.

www.frontiersin.org

FIGURE 2 . (A) displays each local waypoint a l comprising our action space A and their respective coordinates in the robot’s reference frame. (B) and (C) show how we extract the actions demonstrated by the navigation stack as described in Section 3.4.1. In (B) a sub-goal in front of the robot is selected from the global plan from which (C) the closest action, a l , in the action space, is inferred. Panel (D) and (E) show how we extract the actions demonstrated by human or expert user described in Section 3.4.2. (D) shows the starting segment when the robot has been moved to a new pose approximately 2.0 m away from its pose in the starting segment, after the current state, s t was recorded. Finally, in (E) , the action, a l is selected as the one that yields most similar displacement to that observed in (D) .

3.3 Network Architecture

Our model takes in four separate inputs: state features f l and f C respectively, the relative bearing to goal f B , and the robots distance to the goal location f D . f l and f C represent relevant environmental features observed about the robot. As such, the elements in f l and f C are spatially correlated which we leverage by performing a single channel convolution across their respective spatial dimensions with 64 hidden units. Each of the resulting feature maps are passed through a max pooling operation, followed by a dropout regularization of 50%, and finally flattened to a vector that encodes the robots proximity to all obstacles in the immediate vicinity and the presence of visually interesting objects of interest in its field of view. The feature vectors resulting from the above operations and the unperturbed relative bearing to goal f B and distance features f D are concatenated before finally being passed through a fully connected output layer with SoftMax activation, and nine hidden units matching the discrete action labels comprising our action space. Finally, the model is optimized using categorical cross entropy loss.

While we did not perform an exhaustive hyperparameter search for the neural network model, we were able to find a setting that worked well for our purposes. Given the small number of examples we use during training, adding a dropout layer at 50% was necessary to prevent over-fitting. The 64 hidden units in the convolutional and dense layers were enough to provide a large enough number of parameters for the model to learn new behaviors from additional demonstrations without experiencing catastrophic forgetting. We leave further search and refinement of the neural network architecture to future work.

3.4 Training Procedure

Our proposed method uses a two phase training procedure: a pre-training phase followed by a human update phase. First, in the pre-training phase (see Section 3.4.1), an initial navigation policy, π θ 0 , is trained using behavioral cloning on a dataset of demonstration trajectories, D n a v = { τ 0 , τ 1 … . } , where each trajectory, τ, is comprised of a sequence of state action pairs [ ( s 0 , a 0 ) , ( s 1 , a 1 ) , … ] generated by the ROS move_base navigation stack. Second, in the human update training phase (see Section 3.4.2), starting from π θ 0 , we again use behavioral cloning to find our navigation policy π θ * using demonstrations D e x p e r t = { τ 0 , τ 1 … . } from a human tele-operating the robot between a predefined set of start and end locations within the same simulated training environment in a way that adheres to an implicit navigation rule. It should be noted that, in order to reduce effort on the part of a human expert to generate demonstration trajectories, | D n a v | ≫ | D e x p e r t | .

This two phase training procedure allows the user to focus on providing good demonstrations of their navigation preferences in the second phase, that will be used to modify a “vanilla” navigation policy trained in the first phase. The total number of training demonstrations required by our proposed method is far fewer than other works that utilize the classical navigation modules in their training procedure ( Gao et al., 2017 ; Pokle et al., 2019 ). This is because neither one of the training procedures used in our method is trying to create a policy that completely replaces classical navigation modules. Since we still employ these modules at test time, the trained model need not account for kinematic constraints or recovery behaviors.

3.4.1 Pre-Training Procedure

We train the initial policy network, π θ 0 , with demonstrations D n a v only (we describe the collection procedure in Section 4.2) until either convergence or for a fixed number of epochs. We use a categorical cross entropy loss function between the action in the demonstration, a i , and the predicted action label from the network, a i ^ , i.e.,

D n a v is obtained by recording the state-action sequence (i.e., τ) observed by the robot being driven by a modified off-the-shelf navigation system tasked to navigate between randomly-generated start and end locations in the simulated training environment (see Algorithm 1 line 2). The demonstrations are obtained by first observing and recording the robot’s state, s t , and then selecting the closest sub-goal from the navigation system’s global plan that is at least 2.0 m in front of the robot (see Figure 2B ). We then pick the action a t in our action space that is closest to that sub-goal, and task the navigation system’s local planner to move the robot to the local waypoint corresponding to a t (see Figure 2C ). This process is repeated until the robot reaches the goal and results in a demonstration trajectory τ with state-action pairs that align with the state and action space used by the learner. In practice, we stack the m most recent states and use this stack as the input to our learner.

www.frontiersin.org

3.4.2 Training With Human Updates

After the initial navigation policy, π θ 0 , is trained, we update it with several human demonstrations, where the user tele-operates the robot in a way that adheres to one or more semantic rules or preferences (e.g., navigate a wide berth about objects with specific features or always keep said objects to the right of the robot). Demonstrations comprising D e x p e r t were recorded by dividing the tele-operation history into distinct segments of 2.0 m displacement (see Algorithm 1 line 3). The state of the robot at the start of each segment was recorded as s t (see Figure 2D ), and the action a l was selected as the one that would yield a displacement most similar to that observed in the demonstration segment (see Figure 2E ). These demonstrations are then used to introduce human demonstrated navigation preferences or task-specific behaviors by initializing the navigation policy π θ * with π θ 0 and then performing supervised learning using D e x p e r t and the loss function shown in Eq. 1 .

4 Experiments

We perform simulation experiments with the goal of characterizing the efficacy of our approach in terms of both the similarity of the produced navigation trajectories to that of a demonstrator and the overall navigation task success rate. Specifically, the goal is to successfully navigate between a start and goal location while adhering to an implicit navigation style, to navigate a wide berth around any objects with a specific semantic label encountered, that the behavior cloning module learned from human demonstrations as a result of Section 3.4.2. We compare our approach to recent baselines from Pfieffer et al. (2018) and Bojarski et al. (2016) and find that our proposed method outperforms each with respect to both similarity to human demonstrations as well as navigation success rate. We do not provide an empirical analysis comparing our proposed method and baseline performances to traditional navigation stack behaviors. We expect that traditional methods would have a near-perfect navigation completion success ratio. However, they do not have the capacity to learn from demonstrations, and therefore would not be able to modify their behavior to incorporate human navigation preferences.

4.1 Experimental Setup

Experiments were performed using a 0.990 × 0.670 × 0.390   m simulated Clearpath Husky. This Husky is a ground vehicle with 4-wheel differential drive kinematics, a 360° planar lidar, and four on-board cameras, each with a 120° horizontal field of view. Each camera is mounted at one of the four corners on the Husky’s chassis facing outwards, and oriented such that they collectively provide a 360° visual coverage of the Husky’s surroundings.

Experiments were conducted using two different simulators. The first set of experiments uses the Gazebo simulator and focuses on two simplistic environments: a 10 × 12   m training environment ( Figure 3A ) and a 21 × 17   m testing environment ( Figure 3B ). The obstacles within each environment included a large blue box, brick walls, and orange Jersey barriers. Our second set of experiments was performed in a semi-urban environment created using the Unity simulator. Here again we conducted experiments in a 62 × 31   m training environment ( Figure 3C ) and a 48 × 21   m testing environment ( Figure 3D ). The obstacles within these environments include two kinds of crates, several buildings, and lamp posts. The temporal stack is initialized with zero vectors of the same dimensions as our model’s input, s t . The state observed at time t , s t , is pushed into the temporal stack and automatically removes the oldest element, s t − m . The temporal stack is passed as input to the BC model, π θ ′ , from which it predicts the class label, l , of the local waypoint, a l , that is executed by the local planner. All training demonstrations took place in the respective simulator’s training environment, while evaluation of each resulting model took place in both the training and testing environments using navigation tasks (i.e., pairs of starting and ending points) that were not explicitly part of the training set. In particular, we considered six different navigation tasks for evaluation: three tasks in the training environment and three in the testing environment (visualized by the red blue and green paths in Figures 3A–D ). For each model and navigation task evaluated, we performed 50 trials, i.e., we recorded the path taken by each model during the trial and whether the system made it to the destination or not. We consider trajectories that reach within 0.8 m of the goal location successful, and those that collide with an obstacle or exceed a 100 timesteps as failures.

www.frontiersin.org

FIGURE 3 . The top row shows a top down view of the of the (A) training and (B) testing environments simulated in Gazebo. The second row shows a top down view of the (C) training and (D) testing environments simulated in Unity. Images (A) through (D) display the exemplar paths generated by the human demonstrator starting from the red dot to the goal location at the green dot. The bottom row of images displays the raw camera image (E) , the semantically segmented version of the raw image (F) and the object of interest extracted from the semantic image (G) used to generate the visual feature vector f C .

The experimental scenario conducted in the Gazebo-based environments as shown in Figures 3A,B , are two enclosed rooms with large blocks acting as obstacles in an area between the robot’s starting location and the goal location. The large blocks are assigned a blue semantic label. Similarly, the experimental scenario conducted in the Unity-based environments, has several crates acting as obstacles in an area between the robot’s starting location and the goal location (as shown in Figures 3A,B ). Some of the crates are semantically labeled i.e the orange crates and the red and yellow crates in Figure 3E being assigned the blue and red semantic labels respectively in Figure 3F . In both scenarios, the obstacles with the blue semantic labels represent the obstacle that should be traversed in the style of the human demonstrator.

The comparison objective is to empirically measure the similarities of the trajectories generated by a robot, navigating under the control of a model trained using our proposed method, and the experimental baselines, to the exemplar trajectories demonstrated by a human user through both the training and testing environments (i.e., the blue paths shown in Figures 3A–D ). In essence, we should see that a robot, controlled by a model trained using our approach, successfully travels from start to goal, while maintaining a wide distance from semantically labeled obstacles it encounters.

4.2 Demonstration Data Collection

As described in Section 3.4, we first trained an initial behavior cloning model, π θ 0 , to mimic the lowest cost to goal behavior of the existing move_base navigation software in the ROS navigation stack. π θ 0 was trained for 90 epochs, with a batch training size of nine examples per batch. To do this, we used move_base to generate the 200 demonstrations of the robot autonomously navigating from a randomly-sampled start location to a randomly-sampled goal location, within each of the training environments respectively, and record them into D n a v .

To obtain D e x p e r t , the author provided demonstrations completing three different navigation tasks, recording four trajectories per task within each of the training environments respectively (i.e., 12 trajectories in total for each training environment ). The author generated these demonstrations by tele-operating the robot in a way that accomplishes each task while adhering to the following rule: navigate a wide berth around any obstacles encountered that have the semantic label. Afterwords, we update the initial policy π θ 0 with D e x p e r t , to obtain π θ * . During this step, one must pay close attention to the number of training epochs used when updating to avoid catastrophic forgetting of the initial policy behaviors when introducing the human demonstration behaviors. The amount of training epochs used when updating π θ 0 , was experimentally determined to be around 50 epochs, with a batch training size of nine examples per batch. The author also provided 12 additional task demonstrations (four trajectories per task) that are omitted from the training dataset. Three of which were novel tasks within the Gazebo training environment (see Figure 3A ), three in the Gazebo testing environment (see Figure 3B ), three in the Unity training environment (see Figure 3C ) and in the Unity testing environment (see Figure 3D ). These demonstrations are used to evaluate the performance of the models trained using our proposed method and baseline methods.

4.2.1 Data Augmentation

To combat distributional shift in BC, we implemented a data augmentation method inspired by the work of Bojarski et al. (2016) . For a given state-action pair in the demonstration, we produce two additional pairs by synthetically applying a rotational transform to the f l , f C , f B , f D features comprising s t such that they represent the features that would have been observed if the robot was oriented ± 45° from its current pose, and a corrective action that would be necessary to bring the robot back to a familiar state along the demonstrated trajectory under the associated transformation. This augmentation step effectively triples the amount of training data obtained from each demonstration without requiring any additional sensors or demonstrator time. We will henceforth refer to the original state-action pairs as coming from the main frame of reference and distinguish them from these augmented state-action pairs coming from the corrective frame of reference. We also have a specific procedure for temporal stacking corrective frame data before training commences the latest state observation from one of the corrective frames is stacked on top of the m − 1 main frame observations that precede it. This assumes that the corrective frame states will temporally follow the main frame state(s), providing the model with an example of the state progression to a potential failure state and the associated action necessary to correct it.

4.3 Results

The results of our experiments are shown in Figure 4 . They indicate that, for the fixed amount of demonstration data collected in our experiments, the proposed method can generate trajectories more similar to the ground truth human demonstrations with significantly higher completion rates than the models trained with the comparison methods. First, for each evaluation task, we recorded the success rate, i.e., the percentage of time that the system successfully navigated from the start point to the goal point. As seen in the subfigures labeled “Success Rate” in Figures 4A–D , the proposed method maintains a high task success rate in all four evaluation environments while the methods compared against do not. The second way in which we measured performance was trajectory similarity to the demonstrator. Note that, for evaluation, we compared the trajectories generated by each model to the human demonstrations of the evaluation task that were unique to the demonstrated trajectories used to train the model. The subfigures labeled “Hausdorff Distance −1 ” in Figures 4A–D report the inverse modified Hausdorff distance between the successful generated trajectories and the average human demonstration (i.e higher values indicate a greater similarity to the human demonstrations).

www.frontiersin.org

FIGURE 4 . Experimental results evaluating the performances of each model trained using the baseline methods, Bojarski et al. (2016) (red) and Pfeiffer et al. (2018) (green), and our proposed method (violet). The top row shows results of new tasks performed within a (A) training environment, and tasks performed in a different (B) testing environment, both of which were simulated in Gazebo. The bottom row shows experiments conducted in (C) training and (D) testing environments simulated in Unity. The bar plot titled “Trajectory Similarity from Human Demonstrations” (left) uses Modified Hausdorff distance to quantify how similar the paths resulting from the policy rollouts are to an average of all human demonstrated paths for the same task. The bar plot titled “Successful Navigation Rate” (right) depict their success rates. The error bars represent the standard error computed over 50 trials. “***” indicates statistical significance, as computed using a Bonferroni corrected p -value of 0.025.

Additionally, we performed t-tests to determine statistical significance between our proposed method and our experimental baselines using a Bonferroni-corrected p -value threshold of 0.025. We observed that all experimental trials except those conducted in the Gazebo training environment ( Figure 4A ) were statistically significant. We posit that this is likely due the Gazebo training environment being the simplest environment among the four, making it easier for the all models to match the desired behavior demonstrated by the human user. The proposed method outperforms the competitors in this metric, meaning that its generated trajectories were more similar to those driven by the human.

Taken all together, our results demonstrate not only our method’s ability to learn navigation behavior like that which was demonstrated, but also its ability to generalize well beyond the training environment while retaining a high success rate.

5 Discussion

Our experimental results demonstrate the promise of the proposed method for performing Imitation Learning for autonomous robotic navigation. With very little human demonstration, our method was able to learn navigation behaviors like those demonstrated and retain a very high success rate. We posit that our technique was able to outperform others because it is able to appropriately leverage much of the existing machinery of autonomous navigation.

During our experiments, we noted that, while the methods from Bojarski et al. and Pfeiffer et al. were able to learn to navigate around each environment, they had a lower success rate than our approach. For the system proposed by Bojarski et al., which was designed for robust lane following, we observed the agent aimlessly navigating around the environment, avoiding the semantically labeled obstacles but never reaching the goal until the maximum number of time steps is reached. The method proposed by Pfeiffer et al. which does include a notion of global destination, did yield a higher success rate, though, again, not as high as the method proposed here.

While the results we presented do indeed establish the efficacy of our approach relative to the baselines, we also found that it has certain limitations. First, because our method relies on predicting discrete waypoints at a fixed distance, it is limited in the complexity of motion it can execute. While predicting waypoints to send to the local planner, saves us the hours of demonstration data needed to train a navigation policy as robust as an off-the-shelf navigation software, it does restrict the robot from performing highly precise maneuvers that models trained to predict wheel velocity and steering commands directly may be able to capture. Next, we noted that the proposed technique would sometimes generate waypoints within the inflation bounds of obstacles. When this happened, the local planner would still attempt to reach these invalid waypoints, resulting in task failure due to obstacle collision. In fact, the majority of unsuccessful navigation attempts recorded for the proposed system during our experiments were a result of this problem. This issue could possibly be mitigated through the use of explicit action-selection heuristics.

In this paper, we presented a novel method by which robotic agents can adapt their navigation behaviors in response to a demonstration of desirable behavior from a human user. Specifically, the proposed framework involved augmenting a traditional layered navigation system with a new machine learning module that performed BC. By training this module using the proposed procedure, we showed experimentally that the system can learn to imitate stylistic navigation behaviors while retaining the ability to perform successful navigation, even in an unseen environment.

Data Availability Statement

The raw data supporting the conclusions of this article will be made available by the authors, without undue reservation.

Author Contributions

BC-T, GW, and NW developed the proposed technique and the scenarios for evaluation of the proposed concept. BC-T recorded and analyzed the data in addition to generating the results including all figures and all tables. GW wrote the abstract and part of the introduction, BC-T and NW wrote the methods, results and parts of introduction and discussion. GW, KK, and NW gave critical feedback on all parts. BC-T, GW, ES, KK, and NW discussed the results and wrote the overall manuscript together. All authors contributed to the article and approved the submitted version.

Conflict of Interest

The authors declare that the research was conducted in the absence of any commercial or financial relationships that could be construed as a potential conflict of interest.

Supplementary Material

The Supplementary Material for this article can be found online at: https://www.frontiersin.org/articles/10.3389/frobt.2021.627730/full#supplementary-material

Abbeel, Pieter., and Y Ng, Andrew. (2004). Apprenticeship Learning via Inverse Reinforcement Learning. Proceedings of the twenty-first international conference on Machine learning , Banff, Alberta, Canada (New York, NY: ACM ), 1. 10.1145/1015330.1015430

Google Scholar

Argall, Brenna. D., Chernova, Sonia., Veloso, Manuela., and Browning, Brett. (2009). A Survey of Robot Learning from Demonstration. Robotics autonomous Syst. 57 (5), 469–483.

CrossRef Full Text | Google Scholar

Bansal, S., Tolani, V., Gupta, S., Malik, J., and Tomlin, C. (2019). Combining Optimal Control and Learning for Visual Navigation in Novel Environments. Proceedings of the Conference on Robot Learning , 100, 420–429. arXiv preprint arXiv:1903.02531 Available at: http://arxiv.org/abs/1903.02531 .

Bojarski, Mariusz., Davide Del, Testa., Dworakowski, Daniel., Firner, Bernhard., Flepp, Beat., Goyal, Prasoon., et al. (2016). End to End Learning for Self-Driving Cars. CoRR, abs/1604.07316 Available at: http://arxiv.org/abs/1604.07316 .

Chen, Liang-Chieh., George, Papandreou., Schroff, Florian., and Adam, Hartwig. (2017). Rethinking Atrous Convolution for Semantic Image Segmentation. CoRR, abs/1706.05587Available at: http://arxiv.org/abs/1706.05587 .

Doroodgar, B., Yugang Liu, Yugang., and Nejat, G. (2014). A Learning-Based Semi-autonomous Controller for Robotic Exploration of Unknown Disaster Scenes while Searching for Victims. IEEE Trans. Cybern. 44 (12), 2719–2732. doi:10.1109/tcyb.2014.2314294

PubMed Abstract | CrossRef Full Text | Google Scholar

Gao, W., Hsu, D., Sun Lee, W., Shen, S., and Subramanian, K. (2017). Intention-net: Integrating Planning and Deep Learning for Goal-Directed Autonomous Navigation. CoRR, abs/1710.05627 Available at: http://arxiv.org/abs/1710.05627 .

He, Kaiming., Gkioxari, Georgia., Dollár, Piotr., and Ross, B. (2017). Girshick. Mask R-CNN. CoRR, abs/1703.06870 Available at: http://arxiv.org/abs/1703.06870 .

Kalakrishnan, M., Buchli, J., Pastor, P., Mistry, M., and Schaal, S. (2011). Learning, Planning, and Control for Quadruped Locomotion over Challenging Terrain. Int. J. Robotics Res. 30 (2), 236–258. doi:10.1177/0278364910388677

Kavraki, L. E., Svestka, P., Latombe, J.-C., and Overmars, M. H. (1996). Probabilistic Roadmaps for Path Planning in High-Dimensional Configuration Spaces. IEEE Trans. Robot. Automat. 12 (4), 566–580. doi:10.1109/70.508439

Laumond, J.-P., Jacobs, P. E., Taix, M., and Murray, R. M. (1994). A Motion Planner for Nonholonomic mobile Robots. IEEE Trans. Robot. Automat. 10 (5), 577–593. doi:10.1109/70.326564

LaValle, S. M., and Kuffner, J. J. (2001). Randomized Kinodynamic Planning. Int. J. robotics Res. 20 (5), 378–400. doi:10.1177/02783640122067453

Lewis Chiang, Hao-Tien., Faust, Aleksandra., Fiser, Marek., and Francis, Anthony. (2018). Learning Navigation Behaviors End to End. CoRR, abs/1809.10124 Available at: http://arxiv.org/abs/1809.10124 .

Liu, Yugang., Nejat, Goldie., and Doroodgar, Barzin. (2012). Learning Based Semi-autonomous Control for Robots in Urban Search and rescue. IEEE International Symposium on Safety, Security, and Rescue Robotics (SSRR) , College Station, TX , 1–6. IEEE . 10.1109/SSRR.2012.6523902

PubMed Abstract | Google Scholar

Mueller, M., Dosovitskiy, A., Ghanem, B., and Koltun, V. (2018). Driving Policy Transfer via Modularity and Abstraction. Conference on Robot Learning , 1–15.

Koenig, Nathan., and Howard, Andrew. (2004). Design and Use Paradigms for Gazebo, an Open-Source Multi-Robot Simulator. In IEEE/RSJ International Conference on Intelligent Robots and Systems , Sendai, Japan ( New York, NY : IEEE), 2149–2154.

Neu, Gergely., and Szepesvári, Csaba. (2012). Apprenticeship Learning Using Inverse Reinforcement Learning and Gradient Methods, CoRR, abs/1206.5264 Available at: http://arxiv.org/abs/1206.5264 .

Petrovic, Luka. (2018). Motion Planning in High-Dimensional Spaces. CoRR, abs/1806.07457 Available at: http://arxiv.org/abs/1806.07457 .

Pfeiffer, M., Shukla, S., Turchetta, M., Cadena, C., Krause, A., Siegwart, R., et al. (2018). Reinforced Imitation: Sample Efficient Deep Reinforcement Learning for Mapless Navigation by Leveraging Prior Demonstrations. IEEE Robot. Autom. Lett. 3 (4), 4423–4430. doi:10.1109/lra.2018.2869644

Pokle, A., Martín-Martín, R., Goebel, P., Chow, V., Ewald, H. M., Yang, J., et al. (2019). Deep Local Trajectory Replanning and Control for Robot Navigation. CoRR, abs/1905.05279 Available at: http://arxiv.org/abs/1905.05279 .

Ross, Stéphane., Gordon, Geoffrey. J., and Andrew Bagnell, J. (2010). No-regret Reductions for Imitation Learning and Structured Prediction. CoRR, abs/1011.0686 Available at: http://arxiv.org/abs/1011.0686 .

Siva, S., Wigness, Maggie., Rogers, John., and Zhang, Hao. (2019). Robot Adaptation to Unstructured Terrains by Joint Representation and Apprenticeship Learning. Robotics: science and systems , Freiburgim Breisgau, Germany ( Robotics: Science and Systems XV ). doi:10.15607/rss.2019.xv.030

Stein, Gregory. J., Bradley, Christopher., and Roy, Nicholas. (2018). Learning over Subgoals for Efficient Navigation of Structured, Unknown Environments. Conference on Robot Learning ( PMLR ), 213–222.

Thrun, S. (1998). Learning Metric-Topological Maps for Indoor mobile Robot Navigation. Artif. Intelligence 99 (1), 21–71. doi:10.1016/s0004-3702(97)00078-7

Unity Technologies .

Wigness, Maggie., Rogers, John. G., and Navarro-Serment, Luis. E. (2018). Robot Navigation from Human Demonstration: Learning Control Behaviors. IEEE International Conference on Robotics and Automation (ICRA) , Brisbane, QLD, Australia (New York, NY: IEEE ), 1150–1157.

Ziebart, Brian. D., Maas, Andrew. L., Bagnell, J. Andrew., and Anind, Dey, K., and (2008). Maximum Entropy Inverse Reinforcement Learning. AAAI Conference on Artificial Intelligence , Chicago, IL, USA ( New York, NY : AAAI Press), 1433–1438.

Keywords: autonomous navigation, learning from demonstration, imitation learning, human in the loop, robot learning and behavior adaptation

Citation: Cèsar-Tondreau B, Warnell G, Stump E, Kochersberger K and Waytowich NR (2021) Improving Autonomous Robotic Navigation Using Imitation Learning. Front. Robot. AI 8:627730. doi: 10.3389/frobt.2021.627730

Received: 10 November 2020; Accepted: 07 May 2021; Published: 01 June 2021.

Reviewed by:

Copyright © 2021 Cèsar-Tondreau, Warnell, Stump, Kochersberger and Waytowich. This is an open-access article distributed under the terms of the Creative Commons Attribution License (CC BY). The use, distribution or reproduction in other forums is permitted, provided the original author(s) and the copyright owner(s) are credited and that the original publication in this journal is cited, in accordance with accepted academic practice. No use, distribution or reproduction is permitted which does not comply with these terms.

*Correspondence: Brian Cèsar-Tondreau, [email protected]

Disclaimer: All claims expressed in this article are solely those of the authors and do not necessarily represent those of their affiliated organizations, or those of the publisher, the editors and the reviewers. Any product that may be evaluated in this article or claim that may be made by its manufacturer is not guaranteed or endorsed by the publisher.

Subscribe to the PwC Newsletter

Join the community, add a new evaluation result row, robot navigation.

141 papers with code • 4 benchmarks • 14 datasets

The fundamental objective of mobile Robot Navigation is to arrive at a goal position without collision. The mobile robot is supposed to be aware of obstacles and move freely in different working scenarios.

Source: Learning to Navigate from Simulation via Spatial and Semantic Information Synthesis with Noise Model Embedding

Benchmarks Add a Result

--> --> --> --> -->
Trend Dataset Best ModelPaper Code Compare
THDA
VO
VO
SemExp

research on robot navigation

Most implemented papers

Habitat: a platform for embodied ai research.

research on robot navigation

We present Habitat, a platform for research in embodied artificial intelligence (AI).

Depth Prediction Without the Sensors: Leveraging Structure for Unsupervised Learning from Monocular Videos

Models and examples built with TensorFlow

DD-PPO: Learning Near-Perfect PointGoal Navigators from 2.5 Billion Frames

We leverage this scaling to train an agent for 2. 5 Billion steps of experience (the equivalent of 80 years of human experience) -- over 6 months of GPU-time training in under 3 days of wall-clock time with 64 GPUs.

Crowd-Robot Interaction: Crowd-aware Robot Navigation with Attention-based Deep Reinforcement Learning

We propose to (i) rethink pairwise interactions with a self-attention mechanism, and (ii) jointly model Human-Robot as well as Human-Human interactions in the deep reinforcement learning framework.

Gibson Env: Real-World Perception for Embodied Agents

Developing visual perception models for active agents and sensorimotor control are cumbersome to be done in the physical world, as existing algorithms are too slow to efficiently learn in real-time and robots are fragile and costly.

Corners for Layout: End-to-End Layout Recovery from 360 Images

The problem of 3D layout recovery in indoor scenes has been a core research topic for over a decade.

Deep Reinforcement learning for real autonomous mobile robot navigation in indoor environments

In this paper we present our proof of concept for autonomous self-learning robot navigation in an unknown environment for a real robot without a map or planner.

A Graph Neural Network to Model Disruption in Human-Aware Robot Navigation

This paper leverages Graph Neural Networks to model robot disruption considering the movement of the humans and the robot so that the model built can be used by path planning algorithms.

POGEMA: A Benchmark Platform for Cooperative Multi-Agent Navigation

airi-institute/pogema • 20 Jul 2024

Multi-agent reinforcement learning (MARL) has recently excelled in solving challenging cooperative and competitive multi-agent problems in various environments with, mostly, few agents and full observability.

A Fast Ellipse Detector Using Projective Invariant Pruning

dlut-dimt/ellipse-detector • 26 Aug 2016

Detecting elliptical objects from an image is a central task in robot navigation and industrial diagnosis where the detection time is always a critical issue.

research on robot navigation

Long-Range Robotic Navigation via Automated Reinforcement Learning

February 28, 2019

Aleksandra Faust, Senior Research Scientist and Anthony Francis, Senior Software Engineer, Robotics at Google

Automating reinforcement learning with reward and neural network architecture search.
AutoRL (red) success over short distances (up to 10 meters) in several unseen buildings. Compared to hand-tuned (dark-red), (light blue), (blue), and (green).

AutoRL local planner policy transfer to robots in real, unstructured environments
Roadmap being built with 3 Monte Carlo simulations per randomly selected node pair.
The largest map was 288 meters by 163 meters and contains almost 700,000 edges, collected over 4 days using 300 workers in a cluster requiring 1.1 billion collision checks.
Navigation over 100 meters success rates in several buildings. -AutoRL local planner only (blue); (red); (yellow); (green); - PRMs with AutoRL (orange).
On-robot experiments
  • Machine Intelligence

Other posts of interest

research on robot navigation

August 21, 2024

  • Generative AI ·
  • Machine Intelligence ·
  • Natural Language Processing

research on robot navigation

August 16, 2024

  • Data Mining & Modeling ·

research on robot navigation

August 9, 2024

Information

  • Author Services

Initiatives

You are accessing a machine-readable page. In order to be human-readable, please install an RSS reader.

All articles published by MDPI are made immediately available worldwide under an open access license. No special permission is required to reuse all or part of the article published by MDPI, including figures and tables. For articles published under an open access Creative Common CC BY license, any part of the article may be reused without permission provided that the original article is clearly cited. For more information, please refer to https://www.mdpi.com/openaccess .

Feature papers represent the most advanced research with significant potential for high impact in the field. A Feature Paper should be a substantial original Article that involves several techniques or approaches, provides an outlook for future research directions and describes possible research applications.

Feature papers are submitted upon individual invitation or recommendation by the scientific editors and must receive positive feedback from the reviewers.

Editor’s Choice articles are based on recommendations by the scientific editors of MDPI journals from around the world. Editors select a small number of articles recently published in the journal that they believe will be particularly interesting to readers, or important in the respective research area. The aim is to provide a snapshot of some of the most exciting work published in the various research areas of the journal.

Original Submission Date Received: .

  • Active Journals
  • Find a Journal
  • Proceedings Series
  • For Authors
  • For Reviewers
  • For Editors
  • For Librarians
  • For Publishers
  • For Societies
  • For Conference Organizers
  • Open Access Policy
  • Institutional Open Access Program
  • Special Issues Guidelines
  • Editorial Process
  • Research and Publication Ethics
  • Article Processing Charges
  • Testimonials
  • Preprints.org
  • SciProfiles
  • Encyclopedia

sensors-logo

Article Menu

research on robot navigation

  • Subscribe SciFeed
  • Recommended Articles
  • Author Biographies
  • PubMed/Medline
  • Google Scholar
  • on Google Scholar
  • Table of Contents

Find support for a specific problem in the support section of our website.

Please let us know what you think of our products and services.

Visit our dedicated information section to learn more about MDPI.

JSmol Viewer

Research on mobile robot navigation method based on semantic information.

research on robot navigation

1. Introduction

2. mobile robotic systems overview, 2.1. mobile robot navigation technology program, 2.2. general framework of the slam system, 3. map organization and update strategy, 3.1. laser odometry—nonlinear optimization algorithm, 3.2. voxel-based local map construction and updating, 4. combining deep learning for a semantic laser slam system, 4.1. segmentation feature extraction based on ground constraints, 4.2. closed-loop detection and position optimization flow, 5. t-trajectory interpolation strategy.

  • Smooth transitions: Ensuring that the transitions of the robot between connecting target points are smooth to avoid erratic motion.
  • Trajectory Optimization: Interpolation algorithms can be used to generate T-trajectories that optimize the trajectory for a given motion condition, ensuring the shortest path, minimum acceleration/deceleration, and minimum mechanical stress.
  • Velocity Planning: The interpolation algorithm must consider the velocity changes in each part of the T-trajectory to maintain system stability by avoiding excessive speed or slowness.

6. Experimental Results and Analysis

6.1. trajectory interpolation test, 6.2. semantic maps and closed-loop detection experiments, 6.3. large-scale mapping experiment for a corporate campus, 7. conclusions, author contributions, institutional review board statement, informed consent statement, data availability statement, conflicts of interest.

  • Xie, H.; Chen, W.; Fan, Y.; Wang, J. Visual-inertial SLAM in featureless environments on lunar surface. Acta Aeronaut. Astronaut. Sin. 2021 , 42 , 524169. [ Google Scholar ]
  • Xing, Z.; Zhu, X.; Dong, D. DE-SLAM: SLAM for highly dynamic environment. J. Field Robot. 2022 , 39 , 528–542. [ Google Scholar ] [ CrossRef ]
  • Chen, W.; Wang, Y.; Chen, H.; Liu, Y. eil-slam: Depth-enhanced edge-based infrared-lidar slam. J. Field Robot. 2022 , 39 , 117–130. [ Google Scholar ] [ CrossRef ]
  • Zhang, Y.; Song, J.; Ding, Y.; Liu, J. Heterogeneous collaborative SLAM based on fisheye and RGBD cameras. Acta Aeronaut. Astronaut. Sin. 2023 , 44 , 244. [ Google Scholar ]
  • Li, R.; Qi, Y.; Xie, H.; Han, X. Tightly coupled LiDAR SLAM method for unknown environment. Infrared Laser Eng. 2023 , 52 , 135. [ Google Scholar ]
  • Jiang, L.; Liu, L.; Zhou, A.; Han, L.; Li, P. Improved ORB-SLAM algorithm based on motion prediction. J. Zhejiang Univ. 2023 , 57 , 170. [ Google Scholar ]
  • Zhang, L.; Wei, L.; Shen, P.; Wei, W.; Zhu, G.; Song, J. Semantic SLAM based on object detection and improved octomap. IEEE Access 2018 , 6 , 75545–75559. [ Google Scholar ] [ CrossRef ]
  • Chen, X.; Milioto, A.; Palazzolo, E.; Giguere, P.; Behley, J.; Stachniss, C. Suma++: Efficient lidar-based semantic slam. In Proceedings of the 2019 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Macau, China, 3–8 November 2019; pp. 4530–4537. [ Google Scholar ]
  • Chen, W.; Shang, G.; Ji, A.; Zhou, C.; Wang, X.; Xu, C.; Li, Z.; Hu, K. An overview on visual slam: From tradition to semantic. Remote Sens. 2022 , 14 , 3010. [ Google Scholar ] [ CrossRef ]
  • Ran, T.; Yuan, L.; Zhang, J.; Tang, D.; He, L. RS-SLAM: A robust semantic SLAM in dynamic environments based on RGB-D sensor. IEEE Sens. J. 2021 , 21 , 20657–20664. [ Google Scholar ] [ CrossRef ]
  • Tian, Y.; Chang, Y.; Arias, F.H.; Nieto-Granda, C.; How, J.P.; Carlone, L. Kimera-multi: Robust, distributed, dense metric-semantic slam for multi-robot systems. IEEE Trans. Robot. 2022 , 38 , 2022–2038. [ Google Scholar ] [ CrossRef ]
  • Liu, X.; Nardari, G.V.; Cladera, F.; Tao, Y.; Zhou, A.; Donnelly, T.; Qu, C.; Chen, S.W.; Romero, R.A.F.; Taylor, C.J.; et al. Large-scale autonomous flight with real-time semantic slam under dense forest canopy. IEEE Robot. Autom. Lett. 2022 , 7 , 5512–5519. [ Google Scholar ] [ CrossRef ]
  • Qi, C.R.; Yi, L.; Su, H.; Guibas, L.J. Pointnet++: Deep hierarchical feature learning on point sets in a metric space. In Proceedings of the 31st International Conference on Neural Information Processing Systems (NIPS’17), New York, NY, USA, 4–9 December 2017; pp. 5105–5114. [ Google Scholar ]

Click here to enlarge figure

ParameterSpecification
Horizontal field of view360°
Vertical field of view30°
Horizontal angular resolution0.1°/0.2°/0.4°
Frame rate5 Hz/10 Hz/20 Hz
Ranging capability150 m
Accuracy (typical)±2 cm
The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

Sun, R.-H.; Zhao, X.; Wu, C.-D.; Zhang, L.; Zhao, B. Research on Mobile Robot Navigation Method Based on Semantic Information. Sensors 2024 , 24 , 4341. https://doi.org/10.3390/s24134341

Sun R-H, Zhao X, Wu C-D, Zhang L, Zhao B. Research on Mobile Robot Navigation Method Based on Semantic Information. Sensors . 2024; 24(13):4341. https://doi.org/10.3390/s24134341

Sun, Ruo-Huai, Xue Zhao, Cheng-Dong Wu, Lei Zhang, and Bin Zhao. 2024. "Research on Mobile Robot Navigation Method Based on Semantic Information" Sensors 24, no. 13: 4341. https://doi.org/10.3390/s24134341

Article Metrics

Article access statistics, further information, mdpi initiatives, follow mdpi.

MDPI

Subscribe to receive issue release notifications and newsletters from MDPI journals

Captcha Page

We apologize for the inconvenience...

To ensure we keep this website safe, please can you confirm you are a human by ticking the box below.

If you are unable to complete the above request please contact us using the below link, providing a screenshot of your experience.

https://ioppublishing.org/contacts/

Advertisement

Advertisement

Motion planning and control for mobile robot navigation using machine learning: a survey

  • Published: 20 March 2022
  • Volume 46 , pages 569–597, ( 2022 )

Cite this article

research on robot navigation

  • Xuesu Xiao   ORCID: orcid.org/0000-0001-5151-2186 1 ,
  • Garrett Warnell 3 &
  • Peter Stone 1 , 2  

5927 Accesses

83 Citations

Explore all metrics

Moving in complex environments is an essential capability of intelligent mobile robots. Decades of research and engineering have been dedicated to developing sophisticated navigation systems to move mobile robots from one point to another. Despite their overall success, a recently emerging research thrust is devoted to developing machine learning techniques to address the same problem, based in large part on the success of deep learning. However, to date, there has not been much direct comparison between the classical and emerging paradigms to this problem. In this article, we survey recent works that apply machine learning for motion planning and control in mobile robot navigation, within the context of classical navigation systems. The surveyed works are classified into different categories, which delineate the relationship of the learning approaches to classical methods. Based on this classification, we identify common challenges and promising future directions.

This is a preview of subscription content, log in via an institution to check access.

Access this article

Subscribe and save.

  • Get 10 units per month
  • Download Article/Chapter or eBook
  • 1 Unit = 1 Article or 1 Chapter
  • Cancel anytime

Price includes VAT (Russian Federation)

Instant access to the full article PDF.

Rent this article via DeepDyve

Institutional subscriptions

research on robot navigation

Similar content being viewed by others

research on robot navigation

Deep Reinforcement Learning for Autonomous Mobile Robot Navigation

research on robot navigation

Control of Open Mobile Robotic Platform Using Deep Reinforcement Learning

research on robot navigation

Deep Learning Based Path-Planning Using CRNN and A* for Mobile Robots

Explore related subjects.

  • Artificial Intelligence

In mobile robot navigation, “motion planning” mostly focuses on relatively long-term sequences of robot positions, orientations, and their high-order derivatives, while motion control generally refers to relatively low-level motor commands, e.g., linear and angular velocities. However, the line between them is blurry, and we do not adhere to any strict distinction in terminology in this survey.

Becker-Ehmck, P., Karl, M., Peters, J., & van der Smagt, P. (2020). Learning to fly via deep model-based reinforcement learning. arXiv preprint arXiv:2003.08876

Bhardwaj, M., Boots, B., & Mukadam, M. (2020). Differentiable Gaussian process motion planning. In 2020 IEEE international conference on robotics and automation (ICRA) (pp. 10598–10604). IEEE.

Bojarski, M., Del Testa, D., Dworakowski, D., Firner, B., Flepp, B., Goyal, P., Jackel, L. D., Monfort, M., Muller, U., Zhang, J., et al. (2016). End to end learning for self-driving cars. arXiv preprint arXiv:1604.07316

Bruce, J., Sünderhauf, N., Mirowski, P., Hadsell, R., & Milford, M. (2017). One-shot reinforcement learning for robot navigation with interactive replay. arXiv preprint arXiv:1711.10137

Chen, C., Liu, Y., Kreiss, S., & Alahi, A. (2019). Crowd–robot interaction: Crowd-aware robot navigation with attention-based deep reinforcement learning. In 2019 international conference on robotics and automation (ICRA) (pp. 6015–6022). IEEE.

Chen, Y. F., Everett, M., Liu, M., & How, J. P. (2017). Socially aware motion planning with deep reinforcement learning. In 2017 IEEE/RSJ international conference on intelligent robots and systems (IROS) (pp. 1343–1350). IEEE.

Chen, Y. F., Liu, M., Everett, M., & How, J. P. (2017). Decentralized non-communicating multiagent collision avoidance with deep reinforcement learning. In 2017 IEEE international conference on robotics and automation (ICRA) (pp. 285–292). IEEE

Chiang, H. T. L., Faust, A., Fiser, M., & Francis, A. (2019). Learning navigation behaviors end-to-end with autorl. IEEE Robotics and Automation Letters, 4 (2), 2007–2014.

Article   Google Scholar  

Chung, J., Gulcehre, C., Cho, K., & Bengio, Y. (2014). Empirical evaluation of gated recurrent neural networks on sequence modeling. arXiv preprint arXiv:1412.3555

Codevilla, F., Miiller, M., López, A., Koltun, V., & Dosovitskiy, A. (2018). End-to-end driving via conditional imitation learning. In 2018 IEEE international conference on robotics and automation (ICRA) (pp. 1–9). IEEE.

Daniel, K., Nash, A., Koenig, S., & Felner, A. (2010). Theta*: Any-angle path planning on grids. Journal of Artificial Intelligence Research, 39, 533–579.

Article   MathSciNet   Google Scholar  

Dennis, M., Jaques, N., Vinitsky, E., Bayen, A., Russell, S., Critch, A., & Levine, S. (2020). Emergent complexity and zero-shot transfer via unsupervised environment design. In Advances in neural information processing systems (Vol. 33, pp. 13049–13061). Curran Associates, Inc.

Dijkstra, E. W. (1959). A note on two problems in connexion with graphs. Numerische Mathematik, 1 (1), 269–271.

Ding, W., Li, S., Qian, H., & Chen, Y. (2018). Hierarchical reinforcement learning framework towards multi-agent navigation. In 2018 IEEE international conference on robotics and biomimetics (ROBIO) (pp. 237–242). IEEE.

Durrant-Whyte, H., & Bailey, T. (2006). Simultaneous localization and mapping: Part I. IEEE Robotics & Automation Magazine, 13 (2), 99–110.

Elfes, A. (1989). Using occupancy grids for mobile robot perception and navigation. Computer, 22 (6), 46–57.

Everett, M., Chen, Y. F., & How, J. P. (2018). Motion planning among dynamic, decision-making agents with deep reinforcement learning. In 2018 IEEE/RSJ international conference on intelligent robots and systems (IROS) (pp. 3052–3059). IEEE.

Faust, A., Oslund, K., Ramirez, O., Francis, A., Tapia, L., Fiser, M., & Davidson, J. (2018). Prm-rl: Long-range robotic navigation tasks by combining reinforcement learning and sampling-based planning. In 2018 IEEE international conference on robotics and automation (ICRA) (pp. 5113–5120). IEEE.

Fox, D., Burgard, W., & Thrun, S. (1997). The dynamic window approach to collision avoidance. IEEE Robotics & Automation Magazine, 4 (1), 23–33.

Gao, W., Hsu, D., Lee, W. S., Shen, S., & Subramanian, K. (2017). Intention-net: Integrating planning and deep learning for goal-directed autonomous navigation. In Conference on robot learning (pp. 185–194). PMLR.

Giusti, A., Guzzi, J., Cireşan, D. C., He, F. L., Rodríguez, J. P., Fontana, F., et al. (2015). A machine learning approach to visual perception of forest trails for mobile robots. IEEE Robotics and Automation Letters, 1 (2), 661–667.

Godoy, J., Chen, T., Guy, S. J., Karamouzas, I., & Gini, M. (2018). ALAN: Adaptive learning for multi-agent navigation. Autonomous Robots, 42 (8), 1543–1562.

Gupta, S., Davidson, J., Levine, S., Sukthankar, R., & Malik, J. (2017) Cognitive mapping and planning for visual navigation. In Proceedings of the IEEE conference on computer vision and pattern recognition (pp. 2616–2625).

Gupta, S., Fouhey, D., Levine, S., & Malik, J. (2017). Unifying map and landmark based representations for visual navigation. arXiv preprint arXiv:1712.08125

Hart, P., Nilsson, N., & Raphael, B. (1968). A formal basis for the heuristic determination of minimum cost paths. IEEE Transactions on Systems Science and Cybernetics, 4 (2), 100–107. https://doi.org/10.1109/tssc.1968.300136 .

Henry, P., Vollmer, C., Ferris, B., & Fox, D. (2010). Learning to navigate through crowded environments. In 2010 IEEE international conference on robotics and automation (pp. 981–986). IEEE.

Hochreiter, S., & Schmidhuber, J. (1997). Long short-term memory. Neural Computation, 9 (8), 1735–1780.

Jaillet, L., Cortés, J., & Siméon, T. (2010). Sampling-based path planning on configuration-space costmaps. IEEE Transactions on Robotics, 26 (4), 635–646.

Jiang, P., Osteen, P., Wigness, M., & Saripalli, S. (2021). Rellis-3d dataset: Data, benchmarks and analysis. In 2021 IEEE international conference on robotics and automation (ICRA) (pp. 1110–1116). IEEE.

Jin, J., Nguyen, N. M., Sakib, N., Graves, D., Yao, H., & Jagersand, M. (2020). Mapless navigation among dynamics with social-safety-awareness: A reinforcement learning approach from 2d laser scans. In 2020 IEEE international conference on robotics and automation (ICRA) (pp. 6979–6985). IEEE.

Johnson, C., & Kuipers, B. (2018). Socially-aware navigation using topological maps and social norm learning. In Proceedings of the 2018 AAAI/ACM conference on AI, ethics, and society (pp. 151–157).

Kahn, G., Abbeel, P., & Levine, S. (2021). Badgr: An autonomous self-supervised learning-based navigation system. IEEE Robotics and Automation Letters, 6 (2), 1312–1319.

Kahn, G., Villaflor, A., Abbeel, P., & Levine, S. (2018) Composable action-conditioned predictors: Flexible off-policy learning for robot navigation. In Conference on robot learning (pp. 806–816). PMLR.

Kahn, G., Villaflor, A., Ding, B., Abbeel, P., & Levine, S. (2018). Self-supervised deep reinforcement learning with generalized computation graphs for robot navigation. In 2018 IEEE international conference on robotics and automation (ICRA) (pp. 1–8). IEEE.

Karaman, S., & Frazzoli, E. (2011). Sampling-based algorithms for optimal motion planning. The International Journal of Robotics Research, 30 (7), 846–894.

Kavraki, L. E., Svestka, P., Latombe, J. C., & Overmars, M. H. (1996). Probabilistic roadmaps for path planning in high-dimensional configuration spaces. IEEE Transactions on Robotics and Automation, 12 (4), 566–580.

Khan, A., Zhang, C., Atanasov, N., Karydis, K., Kumar, V., & Lee, D. D. (2018). Memory augmented control networks. In International conference on learning representations (ICLR) .

Kim, B., & Pineau, J. (2016). Socially adaptive path planning in human environments using inverse reinforcement learning. International Journal of Social Robotics, 8 (1), 51–66.

Koenig, S., & Likhachev, M. (2002). D \(\hat{\,}{}^{*}\) lite. In AAAI/IAAI (Vol. 15).

Kretzschmar, H., Spies, M., Sprunk, C., & Burgard, W. (2016). Socially compliant mobile robot navigation via inverse reinforcement learning. The International Journal of Robotics Research, 35 (11), 1289–1307.

Kroemer, O., Niekum, S., & Konidaris, G. (2021). A review of robot learning for manipulation: Challenges, representations, and algorithms. Journal of Machine Learning Research, 22, 30–1.

MathSciNet   MATH   Google Scholar  

LaValle, S. M. (1998). Rapidly-exploring random trees: A new tool for path planning.

LaValle, S. M. (2006). Planning algorithms . Cambridge University Press.

LeCunn, Y., Muller, U., Ben, J., Cosatto, E., & Flepp, B. (2006). Off-road obstacle avoidance through end-to-end learning. In Advances in neural information processing systems (pp. 739–746).

Li, M., Jiang, R., Ge, S. S., & Lee, T. H. (2018). Role playing learning for socially concomitant mobile robot navigation. CAAI Transactions on Intelligence Technology, 3 (1), 49–58.

Liang, J., Patel, U., Sathyamoorthy, A. J., & Manocha, D. (2020). Crowd-steer: Realtime smooth and collision-free robot navigation in densely crowded scenarios trained using high-fidelity simulation. In IJCAI (pp. 4221–4228).

Lillicrap, T. P., Hunt, J. J., Pritzel, A., Heess, N., Erez, T., Tassa, Y., Silver, D., & Wierstra, D. (2015). Continuous control with deep reinforcement learning. arXiv preprint arXiv:1509.02971

Lin, J., Wang, L., Gao, F., Shen, S., & Zhang, F. (2019). Flying through a narrow gap using neural network: An end-to-end planning and control approach. In 2019 IEEE/RSJ international conference on intelligent robots and systems (IROS) (pp. 3526–3533). IEEE.

Liu, B., Xiao, X., & Stone, P. (2021). A lifelong learning approach to mobile robot navigation. IEEE Robotics and Automation Letters, 6 (2), 1090–1096.

Long, P., Fanl, T., Liao, X., Liu, W., Zhang, H., & Pan, J. (2018). Towards optimally decentralized multi-robot collision avoidance via deep reinforcement learning. In 2018 IEEE international conference on robotics and automation (ICRA) (pp. 6252–6259). IEEE.

Lopez-Paz, D., & Ranzato, M. (2017). Gradient episodic memory for continual learning. In Advances in neural information processing systems (pp. 6467–6476).

Loquercio, A., Maqueda, A. I., Del-Blanco, C. R., & Scaramuzza, D. (2018). Dronet: Learning to fly by driving. IEEE Robotics and Automation Letters, 3 (2), 1088–1095.

Lu, D. V., Hershberger, D., & Smart, W. D. (2014). Layered costmaps for context-sensitive navigation. In 2014 IEEE/RSJ international conference on intelligent robots and systems (pp. 709–715). IEEE.

Luber, M., Spinello, L., Silva, J., & Arras, K. O. (2012). Socially-aware robot navigation: A learning approach. In 2012 IEEE/RSJ international conference on intelligent robots and systems (pp. 902–907). IEEE.

Martins, G. S., Rocha, R. P., Pais, F. J., & Menezes, P. (2019). Clusternav: Learning-based robust navigation operating in cluttered environments. In 2019 international conference on robotics and automation (ICRA) (pp. 9624–9630). IEEE.

Mnih, V., Badia, A. P., Mirza, M., Graves, A., Lillicrap, T., Harley, T., Silver, D., & Kavukcuoglu, K. (2016). Asynchronous methods for deep reinforcement learning. In International conference on machine learning (pp. 1928–1937).

Nistér, D., Naroditsky, O., & Bergen, J. (2004). Visual odometry. In Proceedings of the 2004 IEEE computer society conference on computer vision and pattern recognition, 2004. CVPR 2004 (Vol. 1, p. I). IEEE.

Okal, B., & Arras, K. O. (2016). Learning socially normative robot navigation behaviors with Bayesian inverse reinforcement learning. In 2016 IEEE international conference on robotics and automation (ICRA) (pp. 2889–2895). IEEE.

OSRF. (2018). Ros wiki move_base. http://wiki.ros.org/move_base

Palmieri, L., & Arras, K. O. (2014). Efficient and smooth RRT motion planning using a novel extend function for wheeled mobile robots. In IEEE/RSJ international conference on intelligent robots and systems (IROS) (pp. 205–211).

Pan, Y., Cheng, C. A., Saigol, K., Lee, K., Yan, X., Theodorou, E. A., & Boots, B. (2020). Imitation learning for agile autonomous driving. The International Journal of Robotics Research, 39 (2–3), 286–302.

Park, J. J. (2016). Graceful navigation for mobile robots in dynamic and uncertain environments. Ph.D. thesis.

Pérez-Higueras, N., Caballero, F., & Merino, L. (2018). Learning human-aware path planning with fully convolutional networks. In 2018 IEEE international conference on robotics and automation (ICRA) (pp. 1–5). IEEE.

Pérez-Higueras, N., Caballero, F., & Merino, L. (2018). Teaching robot navigation behaviors to optimal RRT planners. International Journal of Social Robotics, 10 (2), 235–249.

Pfeiffer, M., Schaeuble, M., Nieto, J., Siegwart, R., & Cadena, C. (2017). From perception to decision: A data-driven approach to end-to-end motion planning for autonomous ground robots. In 2017 IEEE international conference on robotics and automation (ICRA) (pp. 1527–1533). IEEE.

Pfeiffer, M., Schwesinger, U., Sommer, H., Galceran, E., & Siegwart, R. (2016). Predicting actions to act predictably: Cooperative partial motion planning with maximum entropy models. In 2016 IEEE/RSJ international conference on intelligent robots and systems (IROS) (pp. 2096–2101). IEEE.

Pfeiffer, M., Shukla, S., Turchetta, M., Cadena, C., Krause, A., Siegwart, R., & Nieto, J. (2018). Reinforced imitation: Sample efficient deep reinforcement learning for mapless navigation by leveraging prior demonstrations. IEEE Robotics and Automation Letters, 3 (4), 4423–4430.

Pokle, A., Martín-Martín, R., Goebel, P., Chow, V., Ewald, H. M., Yang, J., Wang, Z., Sadeghian, A., Sadigh, D., Savarese, S.,et al. (2019). Deep local trajectory replanning and control for robot navigation. In 2019 international conference on robotics and automation (ICRA) (pp. 5815–5822). IEEE.

Pomerleau, D. A. (1989). Alvinn: An autonomous land vehicle in a neural network. In Advances in neural information processing systems (pp. 305–313).

Quinlan, S., & Khatib, O. (1993). Elastic bands: Connecting path planning and control. In [1993] Proceedings IEEE international conference on robotics and automation (pp. 802–807). IEEE.

Ramachandran, D., & Amir, E. (2007). Bayesian inverse reinforcement learning . In IJCAI (Vol. 7, pp. 2586–2591).

Richter, C., & Roy, N. (2017). Safe visual navigation via deep learning and novelty detection. In Robotics: Science and systems (RSS) .

Ross, S., Gordon, G., & Bagnell, D. (2011). A reduction of imitation learning and structured prediction to no-regret online learning. In Proceedings of the fourteenth international conference on artificial intelligence and statistics (pp. 627–635).

Ross, S., Melik-Barkhudarov, N., Shankar, K. S., Wendel, A., Dey, D., Bagnell, J. A., & Hebert, M. (2013). Learning monocular reactive UAV control in cluttered natural environments. In 2013 IEEE international conference on robotics and automation (pp. 1765–1772). IEEE.

Russell, S. J., & Norvig, P. (2016). Artificial intelligence: A modern approach . Pearson Education Limited.

Sadeghi, F., & Levine, S. (2017). CAD2RL: Real single-image flight without a single real image. In Robotics: Science and systems (RSS) .

Sepulveda, G., Niebles, J. C., & Soto, A. (2018). A deep learning based behavioral approach to indoor autonomous navigation. In 2018 IEEE international conference on robotics and automation (ICRA) (pp. 4646–4653). IEEE.

Sergeant, J., Sünderhauf, N., Milford, M., & Upcroft, B. (2015). Multimodal deep autoencoders for control of a mobile robot. In Proceedings of Australasian conference for robotics and automation (ACRA) .

Shiarlis, K., Messias, J., & Whiteson, S. (2017). Rapidly exploring learning trees. In 2017 IEEE international conference on robotics and automation (ICRA) (pp. 1541–1548). IEEE.

Siva, S., Wigness, M., Rogers, J., & Zhang, H. (2019). Robot adaptation to unstructured terrains by joint representation and apprenticeship learning. In Robotics: Science and systems (RSS) .

Sood, R., Vats, S., & Likhachev, M. (2020). Learning to use adaptive motion primitives in search-based planning for navigation. In 2020 IEEE/RSJ international conference on intelligent robots and systems (IROS) (pp. 6923–6929). IEEE.

Stein, G. J., Bradley, C., & Roy, N. (2018). Learning over subgoals for efficient navigation of structured, unknown environments. In Conference on robot learning (pp. 213–222).

Stratonovich, R. L. (1965). Conditional Markov processes. In Non-linear transformations of stochastic processes (pp. 427–453). Elsevier.

Tai, L., Li, S., & Liu, M. (2016). A deep-network solution towards model-less obstacle avoidance. In 2016 IEEE/RSJ international conference on intelligent robots and systems (IROS) (pp. 2759–2764). IEEE.

Tai, L., & Liu, M. (2016). Deep-learning in mobile robotics-from perception to control systems: A survey on why and why not. arXiv preprint arXiv:1612.07139

Tai, L., Paolo, G., & Liu, M. (2017). Virtual-to-real deep reinforcement learning: Continuous control of mobile robots for mapless navigation. In 2017 IEEE/RSJ international conference on intelligent robots and systems (IROS) (pp. 31–36). IEEE.

Tai, L., Zhang, J., Liu, M., Boedecker, J., & Burgard, W. (2016). A survey of deep network solutions for learning control in robotics: From reinforcement to imitation. arXiv preprint arXiv:1612.07139

Tai, L., Zhang, J., Liu, M., & Burgard, W. (2018). Socially compliant navigation through raw depth inputs with generative adversarial imitation learning. In 2018 IEEE international conference on robotics and automation (ICRA) (pp. 1111–1117). IEEE.

Tamar, A., Wu, Y., Thomas, G., Levine, S., & Abbeel, P. (2016). Value iteration networks. In Advances in neural information processing systems (pp. 2154–2162).

Teso-Fz-Betoño, D., Zulueta, E., Fernandez-Gamiz, U., Saenz-Aguirre, A., & Martinez, R. (2019). Predictive dynamic window approach development with artificial neural fuzzy inference improvement. Electronics, 8 (9), 935.

Thrun, S. (1995). An approach to learning mobile robot navigation. Robotics and Autonomous Systems, 15 (4), 301–319.

Ullman, S. (1979). The interpretation of structure from motion. Proceedings of the Royal Society of London. Series B. Biological Sciences, 203 (1153), 405–426.

Google Scholar  

Van Den Berg, J., Guy, S. J., Lin, M., & Manocha, D. (2011). Reciprocal n-body collision avoidance. In Robotics research (pp. 3–19). Springer.

Wang, Y., He, H., & Sun, C. (2018). Learning to navigate through complex dynamic environment with modular deep reinforcement learning. IEEE Transactions on Games, 10 (4), 400–412.

Wang, Z., Xiao, X., Liu, B., Warnell, G., & Stone, P. (2021). Appli: Adaptive planner parameter learning from interventions. In 2021 IEEE international conference on robotics and automation (ICRA) (pp. 6079–6085). IEEE.

Wang, Z., Xiao, X., Nettekoven, A. J., Umasankar, K., Singh, A., Bommakanti, S., Topcu, U., & Stone, P. (2021). From agile ground to aerial navigation: Learning from learned hallucination. In 2021 IEEE/RSJ international conference on intelligent robots and systems (IROS) . IEEE.

Wang, Z., Xiao, X., Warnell, G., & Stone, P. (2021). Apple: Adaptive planner parameter learning from evaluative feedback. IEEE Robotics and Automation Letters, 6 (4), 7744–7749.

Watkins, C. J., & Dayan, P. (1992). Q-learning. Machine Learning, 8 (3–4), 279–292.

MATH   Google Scholar  

Wigness, M., Rogers, J. G., & Navarro-Serment, L. E. (2018). Robot navigation from human demonstration: Learning control behaviors. In 2018 IEEE international conference on robotics and automation (ICRA) (pp. 1150–1157). IEEE.

Xiao, X., Biswas, J., & Stone, P. (2021a). Learning inverse kinodynamics for accurate high-speed off-road navigation on unstructured terrain. IEEE Robotics and Automation Letters, 6 (3), 6054–6060.

Xiao, X., Liu, B., & Stone, P. (2021b). Agile robot navigation through hallucinated learning and sober deployment. In 2021 IEEE international conference on robotics and automation (ICRA) (pp. 7316–7322). IEEE.

Xiao, X., Liu, B., Warnell, G., Fink, J., & Stone, P. (2020). Appld: Adaptive planner parameter learning from demonstration. IEEE Robotics and Automation Letters, 5 (3), 4541–4547.

Xiao, X., Liu, B., Warnell, G., & Stone, P. (2021c). Toward agile maneuvers in highly constrained spaces: Learning from hallucination. IEEE Robotics and Automation Letters, 6 (2), 1503–1510.

Xiao, X., Wang, Z., Xu, Z., Liu, B., Warnell, G., Dhamankar, G., Nair, A., & Stone, P. (2021d). Appl: Adaptive planner parameter learning. arXiv preprint arXiv:2105.07620

Xie, L., Wang, S., Rosa, S., Markham, A., & Trigoni, N. (2018). Learning with training wheels: Speeding up training with a simple controller for deep reinforcement learning. In 2018 IEEE international conference on robotics and automation (ICRA) (pp. 6276–6283). IEEE.

Xu, Z., Dhamankar, G., Nair, A., Xiao, X., Warnell, G., Liu, B., Wang, Z., & Stone, P. (2021). Applr: Adaptive planner parameter learning from reinforcement. In 2021 IEEE international conference on robotics and automation (ICRA) (pp. 6086–6092). IEEE.

Yao, X., Zhang, J., & Oh, J. (2019). Following social groups: Socially compliant autonomous navigation in dense crowds. arXiv preprint arXiv:1911.12063

Zeng, J., Ju, R., Qin, L., Hu, Y., Yin, Q., & Hu, C. (2019). Navigation in unknown dynamic environments based on deep reinforcement learning. Sensors, 19 (18), 3837.

Zhang, J., Springenberg, J. T., Boedecker, J., & Burgard, W. (2017). Deep reinforcement learning with successor features for navigation across similar environments. In 2017 IEEE/RSJ international conference on intelligent robots and systems (IROS) (pp. 2371–2378). IEEE.

Zhang, J., Tai, L., Boedecker, J., Burgard, W., & Liu, M. (2017). Neural slam: Learning to explore with external memory. arXiv preprint arXiv:1706.09520

Zhang, T., Kahn, G., Levine, S., & Abbeel, P. (2016). Learning deep control policies for autonomous aerial vehicles with MPC-guided policy search. In 2016 IEEE international conference on robotics and automation (ICRA) (pp. 528–535). IEEE.

Zhao, L., & Roh, M. I. (2019). Colregs-compliant multiship collision avoidance based on deep reinforcement learning. Ocean Engineering, 191, 106436.

Zhelo, O., Zhang, J., Tai, L., Liu, M., & Burgard, W. (2018). Curiosity-driven exploration for mapless navigation with deep reinforcement learning. arXiv preprint arXiv:1804.00456

Zhou, X., Gao, Y., & Guan, L. (2019). Towards goal-directed navigation through combining learning based global and local planners. Sensors, 19 (1), 176.

Zhu, Y., Mottaghi, R., Kolve, E., Lim, J. J., Gupta, A., Fei-Fei, L., & Farhadi, A. (2017). Target-driven visual navigation in indoor scenes using deep reinforcement learning. In 2017 IEEE international conference on robotics and automation (ICRA) (pp. 3357–3364). IEEE.

Zhu, Y., Schwab, D., & Veloso, M. (2019). Learning primitive skills for mobile robots. In 2019 international conference on robotics and automation (ICRA) (pp. 7597–7603). IEEE.

Ziebart, B. D., Maas, A. L., Bagnell, J. A., & Dey, A. K. (2008). Maximum entropy inverse reinforcement learning. In AAAI (Vol. 8, pp. 1433–1438).

Download references

Acknowledgements

This work has taken place in the Learning Agents Research Group (LARG) at the Artificial Intelligence Laboratory, The University of Texas at Austin. LARG research is supported in part by Grants from the National Science Foundation (CPS-1739964, IIS-1724157, NRI-1925082), the Office of Naval Research (N00014-18-2243), Future of Life Institute (RFP2-000), Army Research Office (W911NF-19-2-0333), DARPA, Lockheed Martin, General Motors, and Bosch. The views and conclusions contained in this document are those of the authors alone. Peter Stone serves as the Executive Director of Sony AI America and receives financial compensation for this work. The terms of this arrangement have been reviewed and approved by the University of Texas at Austin in accordance with its policy on objectivity in research. We would also like to thank Yifeng Zhu for helpful discussions and suggestions, and Siddharth Rajesh Desai for helping editing and refining the language for this survey.

Author information

Authors and affiliations.

Department of Computer Science, The University of Texas at Austin, Austin, TX, 78712, USA

Xuesu Xiao, Bo Liu & Peter Stone

Sony AI, Tokyo, Japan

Peter Stone

Computational and Information Sciences Directorate, Army Research Laboratory, Adelphi, MD, 20783, USA

Garrett Warnell

You can also search for this author in PubMed   Google Scholar

Corresponding author

Correspondence to Xuesu Xiao .

Additional information

Publisher's note.

Springer Nature remains neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Rights and permissions

Reprints and permissions

About this article

Xiao, X., Liu, B., Warnell, G. et al. Motion planning and control for mobile robot navigation using machine learning: a survey. Auton Robot 46 , 569–597 (2022). https://doi.org/10.1007/s10514-022-10039-8

Download citation

Received : 24 March 2021

Accepted : 25 February 2022

Published : 20 March 2022

Issue Date : June 2022

DOI : https://doi.org/10.1007/s10514-022-10039-8

Share this article

Anyone you share the following link with will be able to read this content:

Sorry, a shareable link is not currently available for this article.

Provided by the Springer Nature SharedIt content-sharing initiative

  • Mobile robot navigation
  • Machine learning
  • Motion planning
  • Motion control
  • Find a journal
  • Publish with us
  • Track your research

arXiv's Accessibility Forum starts next month!

Help | Advanced Search

Computer Science > Robotics

Title: a survey on socially aware robot navigation: taxonomy and future challenges.

Abstract: Socially aware robot navigation is gaining popularity with the increase in delivery and assistive robots. The research is further fueled by a need for socially aware navigation skills in autonomous vehicles to move safely and appropriately in spaces shared with humans. Although most of these are ground robots, drones are also entering the field. In this paper, we present a literature survey of the works on socially aware robot navigation in the past 10 years. We propose four different faceted taxonomies to navigate the literature and examine the field from four different perspectives. Through the taxonomic review, we discuss the current research directions and the extending scope of applications in various domains. Further, we put forward a list of current research opportunities and present a discussion on possible future challenges that are likely to emerge in the field.
Subjects: Robotics (cs.RO)
Cite as: [cs.RO]
  (or [cs.RO] for this version)
  Focus to learn more arXiv-issued DOI via DataCite
: Focus to learn more DOI(s) linking to related resources

Submission history

Access paper:.

  • Other Formats

References & Citations

  • Google Scholar
  • Semantic Scholar

BibTeX formatted citation

BibSonomy logo

Bibliographic and Citation Tools

Code, data and media associated with this article, recommenders and search tools.

  • Institution

arXivLabs: experimental projects with community collaborators

arXivLabs is a framework that allows collaborators to develop and share new arXiv features directly on our website.

Both individuals and organizations that work with arXivLabs have embraced and accepted our values of openness, community, excellence, and user data privacy. arXiv is committed to these values and only works with partners that adhere to them.

Have an idea for a project that will add value for arXiv's community? Learn more about arXivLabs .

share this!

August 22, 2024

This article has been reviewed according to Science X's editorial process and policies . Editors have highlighted the following attributes while ensuring the content's credibility:

fact-checked

peer-reviewed publication

The future of robotics: Brain-inspired navigation technologies paving the way

by Beijing Institute of Technology Press Co., Ltd

The future of robotics: Brain-inspired technologies paving the way

In the ever-evolving field of robotics, a groundbreaking approach has emerged, revolutionizing how robots perceive, navigate, and interact with their environments. This new frontier, known as brain-inspired navigation technology, integrates insights from neuroscience into robotics, offering enhanced capabilities and efficiency.

A paper on this topic, " A Review of Brain-Inspired Cognition and Navigation Technology for Mobile Robots ," was published in the journal Cyborg and Bionic Systems on June 27, 2024.

Brain-inspired navigation technologies are not just a mere improvement over traditional methods; they represent a paradigm shift. By mimicking the neural mechanisms of animals, these technologies provide robots with the ability to navigate through complex and unknown terrains with unprecedented accuracy and adaptability.

At the heart of this technology lies the concept of spatial cognition, which is central to how animals, including humans, navigate their environments. Spatial cognition involves the brain's ability to organize and interpret spatial data for navigation and memory.

Robots equipped with brain-inspired navigation systems utilize a multi-layered network model that integrates sensory data from multiple sources. This model allows the robot to create a "cognitive map" of its surroundings, much like the neural maps created by the hippocampus in the human brain .

One of the significant advantages of brain-inspired navigation is its robustness in challenging environments. Traditional navigation systems often struggle with dynamic and unpredictable settings, where the reliance on pre-mapped routes and landmarks can lead to failures.

In contrast, brain-inspired systems continuously learn and adapt, improving their navigational strategies over time. This capability is particularly beneficial in environments like disaster zones or extraterrestrial surfaces, where prior mapping is either impossible or impractical.

Moreover, these systems significantly reduce energy consumption and computational needs. By focusing only on essential data and employing efficient neural network models, robots can operate longer and perform more complex tasks without the need for frequent recharging or maintenance.

The technology's applications are vast and varied. For instance, autonomous vehicles equipped with brain-inspired systems could navigate more safely and efficiently, reacting in real-time to sudden changes in traffic conditions or road layouts. Similarly, drones used for delivery services could plan their routes more effectively, avoiding obstacles and optimizing delivery times.

Despite its promising potential, the development of brain-inspired navigation technology faces several challenges. Integrating biological principles into mechanical systems is inherently complex, requiring multidisciplinary efforts from fields such as neuroscience, cognitive science , robotics, and artificial intelligence. Moreover, these systems must be scalable and versatile enough to be customized for different types of robotic platforms and applications.

As researchers continue to unravel the mysteries of the brain's navigational capabilities, the future of robotics looks increasingly intertwined with the principles of neuroscience. The collaboration across disciplines promises not only to advance our understanding of the brain but also to pave the way for a new generation of intelligent robots. These robots will not only assist in mundane tasks but also perform critical roles in search and rescue operations, planetary exploration, and much more.

In conclusion, brain-inspired navigation technology represents a significant leap forward in robotics, merging the abstract with the applied, the biological with the mechanical, and the theoretical with the practical. As this technology continues to evolve, it will undoubtedly open new horizons for robotic applications, making machines an even more integral part of our daily lives and work.

Explore further

Feedback to editors

research on robot navigation

Resin made from biomass advances method for manufacturing recyclable wind turbine blades

6 hours ago

research on robot navigation

Sprayable gels could protect buildings during wildfires

7 hours ago

research on robot navigation

Researchers propose a smaller, more noise-tolerant quantum factoring circuit for cryptography

8 hours ago

research on robot navigation

Researchers unleash machine learning in designing advanced lattice structures

Aug 22, 2024

research on robot navigation

Redox-active metal-organic framework developed for Li batteries in freezing conditions

research on robot navigation

Flexible nanogenerator with enhanced power density could one day rival the power of solar panels

research on robot navigation

New method allows AI to learn indefinitely

research on robot navigation

Self-improving AI method increases 3D-printing efficiency

research on robot navigation

Scientists invent a hot-emitter transistor for future high-performance, low-power, multifunctional devices

research on robot navigation

Improving workplace safety: The Bilateral Back Extensor Exosuit

Related stories.

research on robot navigation

Bumblebees' sense of direction rivals that of humans, study shows

Aug 14, 2024

research on robot navigation

Navigating new horizons: Pioneering AI framework enhances robot efficiency and planning

May 31, 2024

research on robot navigation

Scientists establish brain-inspired network model to bridge AI and neuroscience

Aug 21, 2024

research on robot navigation

A method to enable safe mobile robot navigation in dynamic environments

Jun 21, 2024

research on robot navigation

Transformative FiBa soft actuators pave the way for future soft robotics

Aug 16, 2024

research on robot navigation

Brain-inspired intelligent robotics: Theoretical analysis and systematic application

Apr 10, 2023

Recommended for you

research on robot navigation

Designing the ideal soft gripper for diverse functionalities

research on robot navigation

Researchers train a robot dog to combat invasive fire ants

research on robot navigation

Scalable woven actuators offer new possibilities for robotics and wearable devices

Aug 20, 2024

research on robot navigation

AI assistant monitors teamwork to promote effective collaboration

research on robot navigation

Simplified robotic gripper can still tackle complex object manipulation tasks

Aug 17, 2024

Let us know if there is a problem with our content

Use this form if you have come across a typo, inaccuracy or would like to send an edit request for the content on this page. For general inquiries, please use our contact form . For general feedback, use the public comments section below (please adhere to guidelines ).

Please select the most appropriate category to facilitate processing of your request

Thank you for taking time to provide your feedback to the editors.

Your feedback is important to us. However, we do not guarantee individual replies due to the high volume of messages.

E-mail the story

Your email address is used only to let the recipient know who sent the email. Neither your address nor the recipient's address will be used for any other purpose. The information you enter will appear in your e-mail message and is not retained by Tech Xplore in any form.

Your Privacy

This site uses cookies to assist with navigation, analyse your use of our services, collect data for ads personalisation and provide content from third parties. By using our site, you acknowledge that you have read and understand our Privacy Policy and Terms of Use .

E-mail newsletter

New center to improve robot dexterity selected to receive up to $52 million

Bilge Mutlu (People and Robots Lab) will support Human AugmentatioN via Dexterity (HAND), an NSF-funded collaboration dedicated to improving robot dexterity.

A large multi-institutional collaboration has received $26 million from the National Science Foundation (NSF) to launch a new Engineering Research Center (ERC) dedicated to revolutionizing the ability of robots to amplify human labor. 

research on robot navigation

The NSF grant will fund the new center across five years, with the ability to renew for another $26 million for an additional five years. Led by Northwestern University, UW–Madison’ People and Robots Lab Director Bilge Mutlu will support efforts alongside researchers from Carnegie-Mellon University, Florida A&M, Massachusetts Institute of Technology, Texas A&M, and Syracuse University.

Called Human AugmentatioN via Dexterity (HAND) , the new ERC will transform dexterous robot hands into versatile, easy-to-integrate tools. By developing technologies that enable human-like robotic dexterity, the center aims to create robots capable of intelligent and versatile grasping, fine motor skills and hand-eye coordination. These functions will improve robots’ ability to assist humans with manufacturing, caregiving, handling precious or dangerous materials and more.

ERC Director J. Edward Colgate emphasized the impact this work will have across industry, the economy, and the scientific community at large. “Rapid advances in artificial intelligence (AI) have created an incredible opportunity to make robot manipulators accessible to small American manufacturers, people with motor impairments and many others who might benefit,” Colgate said. “A huge challenge, however, is what we put at the end of the robot’s arm. Today’s two-jaw grippers are far too limited. HAND’s fundamental research will lead to robots with dexterous and versatile hands, manual skills and intuitive interfaces that anyone can learn to use.”

research on robot navigation

According to Mutlu, “Robots today can only do simple things like picking things up from here and putting them there, and HAND will change that.” As a part of achieving this goal, UW–Madison’s research will contribute to one of the main “thrusts” of the center that will “develop new interfaces for programming, controlling, teaching, and supervising dexterous robots that domain experts with little expertise in robotics can effectively and easily use.” 

The interdisciplinary team will help develop and prepare a diverse workforce for an entirely new field of study focused on dexterous robots and foster a culture that nourishes inclusivity and ensures equitable access to new technologies. Potential outcomes will include increased worker productivity, improved job opportunities, reshoring of manufacturing, reduced supply chain vulnerability, enhanced food safety, improved quality of life and democratization of the benefits of robotics.

Since its founding in 1985, the ERC program has supported convergent research, education and technology translation at U.S. universities. Each ERC unites members from academia, industry and government to produce transformational engineered systems along with engineering graduates who are adept at innovation and primed for leadership in the global economy. 

“NSF’s Engineering Research Centers ask big questions in order to catalyze solutions with far-reaching impacts,” said NSF Director Sethuraman Panchanathan. “NSF Engineering Research Centers are powerhouses of discovery and innovation, bringing America’s great engineering minds to bear on our toughest challenges. By collaborating with industry and training the workforce of the future, ERCs create an innovation ecosystem that can accelerate engineering innovations, producing tremendous economic and societal benefits for the nation.”

IMAGES

  1. Applied Sciences

    research on robot navigation

  2. Robot navigation framework [14].

    research on robot navigation

  3. Robot navigation framework [14].

    research on robot navigation

  4. An indoor mobile robot navigation technique using odometry and

    research on robot navigation

  5. Autonomous robot navigation in the vineyard

    research on robot navigation

  6. Robot Learning Research

    research on robot navigation

COMMENTS

  1. A systematic review on recent advances in autonomous mobile robot

    Recent years have seen a dramatic rise in the popularity of autonomous mobile robots (AMRs) due to their practicality and potential uses in the modern world. Path planning is among the most important tasks in AMR navigation since it demands the robot to identify the best route based on desired performance criteria such as safety margin ...

  2. A comprehensive study for robot navigation techniques

    The paper contains brief study for the methods involve in navigation system along with algorithms used for optimizing the path for mobile robot. In modern days, robots have fundamental importance in every field. The robots are helping humanity to reduce men labor and efforts. 1.

  3. A review: On path planning strategies for navigation of mobile robot

    This paper presents the rigorous study of mobile robot navigation techniques used so far. The step by step investigations of classical and reactive approaches are made here to understand the development of path planning strategies in various environmental conditions and to identify research gap. The classical approaches such as cell ...

  4. Advancements and Challenges in Mobile Robot Navigation: A ...

    Mobile robot navigation has been a very popular topic of practice among researchers since a while. With the goal of enhancing the autonomy in mobile robot navigation, numerous algorithms (traditional AI-based, swarm intelligence-based, self-learning-based) have been built and implemented independently, and also in blended manners. Nevertheless, the problem of efficient autonomous robot ...

  5. [2212.12808] A Comprehensive Review on Autonomous Navigation

    This paper tries to provide a comprehensive review of autonomous mobile robots covering topics such as sensor types, mobile robot platforms, simulation tools, path planning and following, sensor fusion methods, obstacle avoidance, and SLAM. The urge to present a survey paper is twofold. First, autonomous navigation field evolves fast so writing ...

  6. Toward Intelligent Navigation for Autonomous Mobile Robots ...

    This chapter provides a comprehensive review of the literature on learning-based approaches to mobile robot navigation. The authors review existing research on end-to-end learning, subsystem replacement, and component adaptation approaches and evaluate each approach based on several criteria such as performance, interpretability, safety, and scalability.

  7. Frontiers

    FIGURE 2.(A) displays each local waypoint a l comprising our action space A and their respective coordinates in the robot's reference frame. (B) and (C) show how we extract the actions demonstrated by the navigation stack as described in Section 3.4.1. In (B) a sub-goal in front of the robot is selected from the global plan from which (C) the closest action, a l, in the action space, is ...

  8. Mobile Robot Navigation Using Deep Reinforcement Learning

    In addition, vision-based navigation has an exponentially spreading impact on robot navigation research by considering the ubiquity of a commercial camera and the semantic information embedded in an RGB image. Localization is one of the most important skills required by an autonomous robot, as recognizing the robot's own position is a ...

  9. Learning robust autonomous navigation and locomotion for ...

    Wheeled-legged robots offer a comprehensive solution that addresses these requirements (5-8).Our research focuses on developing a wheeled-legged robot, as depicted in Fig. 1, where actuated wheels are integrated with its legs ().Unlike other logistics platforms, this design empowers the robot to operate effectively over long distances, enabling high-speed locomotion on moderate surfaces ...

  10. Robot Navigation

    The fundamental objective of mobile **Robot Navigation** is to arrive at a goal position without collision. The mobile robot is supposed to be aware of obstacles and move freely in different working scenarios. ... Recent research on mobile robot navigation has focused on socially aware navigation in crowded environments. 4. 15 Mar 2024 Paper ...

  11. Robot Navigation

    Robot Navigation. 141 papers with code • 4 benchmarks • 14 datasets. The fundamental objective of mobile Robot Navigation is to arrive at a goal position without collision. The mobile robot is supposed to be aware of obstacles and move freely in different working scenarios. Source: Learning to Navigate from Simulation via Spatial and ...

  12. Navigation in Large Groups of Robots

    Purpose of Review As robots become more ubiquitous, research in large-scale robot navigation has gained more focus given their potential real-world applications. This review intends to provide a summary of recent advances on the field of multi-robot navigation, focusing on cases where scale is an important attribute of the system. Recent Findings Experimental evaluation of a large number of ...

  13. Visual route following for tiny autonomous robots

    For navigation, robots often rely either on external infrastructure or on mapping-based navigation algorithms that are generally associated with high computational demands. van Dijk et al. have now developed an insect-inspired approach for visual navigation of resource-constrained miniature drones by exploiting both visual homing and odometry.The framework was tested on a 56-g drone, which was ...

  14. Recent advances in vision-based indoor navigation: A systematic

    Robot navigation systems. Typically, robot navigation systems and blind navigational aids have similar mechanism. In this regard, a recent study [101] has used deep a convolutional neural network (DCNN) for robot indoor navigation, which can also be generalized for general navigation of the people. Moreover, collision detection and avoidance ...

  15. A novel mobile robot navigation method based on deep reinforcement

    In the early days, the emergence of simultaneous localization and mapping 1 (SLAM) technology has significant significance for mobile robot navigation. SLAM is a process in which robots are equipped with sensors such as vision, laser, and odometer to construct a map while understanding the unknown environment. 2,3 The current research method of SLAM problem is mainly by installing multi-type ...

  16. Safe path planning of mobile robot based on improved particle swarm

    Path planning is a fundamental aspect of mobile robot navigation, playing a crucial role in enabling robots to autonomously navigate while avoiding obstacles. Nevertheless, traditional path planning algorithms face navigation challenges, including obstacle avoidance and the potential for getting stuck in local minima or deadlocks along the path.

  17. Long-Range Robotic Navigation via Automated ...

    Long-Range Robotic Navigation via Automated Reinforcement Learning. In the United States alone, there are 3 million people with a mobility impairment that prevents them from ever leaving their homes. Service robots that can autonomously navigate long distances can improve the independence of people with limited mobility, for example, by ...

  18. [2407.02539] Research on Autonomous Robots Navigation based on

    In recent years, it has become one of the key methods to achieve autonomous navigation of robots. In this work, an autonomous robot navigation method based on reinforcement learning is introduced. We use the Deep Q Network (DQN) and Proximal Policy Optimization (PPO) models to optimize the path planning and decision-making process through the ...

  19. (PDF) A comprehensive study for robot navigation techniques

    Abstract: An intelligent autonomous robot is required in various applications such. as space, transportation, industry, and defense. Mobile robots can also perform. several tasks like material ...

  20. (PDF) Core Challenges of Social Robot Navigation: A Survey

    Core Challenges of Social Robot Navigation: A Survey. February 2023. ACM Transactions on Human-Robot Interaction 12 (3) DOI: 10.1145/3583741. Authors: Christoforos Mavrogiannis. University of ...

  21. (PDF) Mobile Robot Navigation and Obstacle Avoidance ...

    Abstract. Mobile robot is an autonomous agent capable of navigating intelligently anywhere using sensor-actuator control techniques. The applications of the autonomous mobile robot in many fields ...

  22. Sensors

    This paper proposes a solution to the problem of mobile robot navigation and trajectory interpolation in dynamic environments with large scenes. The solution combines a semantic laser SLAM system that utilizes deep learning and a trajectory interpolation algorithm. The paper first introduces some open-source laser SLAM algorithms and then elaborates in detail on the general framework of the ...

  23. Research on laser-based mobile robot SLAM and autonomous navigation

    Abstract. SLAM (Simultaneous Localization and Mapping) and autonomous navigation systems, as fundamental components of mobile robots, largely determine their ability to accomplish tasks. While research on laser-based SLAM and autonomous navigation algorithms in simulated environments has achieved significant success, there is limited research ...

  24. Motion planning and control for mobile robot navigation using machine

    Moving in complex environments is an essential capability of intelligent mobile robots. Decades of research and engineering have been dedicated to developing sophisticated navigation systems to move mobile robots from one point to another. Despite their overall success, a recently emerging research thrust is devoted to developing machine learning techniques to address the same problem, based ...

  25. [2311.06922] A Survey on Socially Aware Robot Navigation: Taxonomy and

    Socially aware robot navigation is gaining popularity with the increase in delivery and assistive robots. The research is further fueled by a need for socially aware navigation skills in autonomous vehicles to move safely and appropriately in spaces shared with humans. Although most of these are ground robots, drones are also entering the field. In this paper, we present a literature survey of ...

  26. The future of robotics: Brain-inspired navigation technologies paving

    In the ever-evolving field of robotics, a groundbreaking approach has emerged, revolutionizing how robots perceive, navigate, and interact with their environments. This new frontier, known as brain-inspired navigation technology, integrates insights from neuroscience into robotics, offering enhanced capabilities and efficiency.

  27. Integration of Global Navigation Satellite System and Ultra-Wide Band

    With the expansion of autonomous mobile robot system applications in outdoor scenarios, there is a need for precise positioning information to aid robot navigation. Unlike indoor robotic applications where high-accuracy positioning systems exist, most outdoor robot positioning systems are based on Global Navigation Satellite System (GNSS), which at times fails to achieve the desired precision ...

  28. Beetle that pushes dung with the help of 100 billion ...

    An insect species that evolved 130 million years ago is the inspiration for a new research study to improve navigation systems in drones, robots, and orbiting satellites.

  29. (PDF) Beyond Shortsighted Navigation: Merging Best View Trajectory

    Our approach to Long Horizon Viewpoint Planning (LHVP), enables the robot to autonomously navigate and collect environmental data optimizing for coverage over the horizon of the patrol.

  30. New center to improve robot dexterity selected to receive up to $52

    Bilge Mutlu (People and Robots Lab) will support Human AugmentatioN via Dexterity (HAND), an NSF-funded collaboration dedicated to improving robot dexterity. A large multi-institutional collaboration has received $26 million from the National Science Foundation (NSF) to launch a new Engineering Research Center (ERC) dedicated to revolutionizing ...