Next Article in Journal
Experimental Study on the Dynamic Characteristics of Hydro-Pneumatic Semi-Active Suspensions for Agricultural Tractor Cabins
Next Article in Special Issue
Sampling-Based Motion Planning for Free-Floating Space Robot without Inverse Kinematics
Previous Article in Journal
Curcumin Innovative Delivery Forms: Paving the ‘Yellow Brick Road’ of Antitumoral Phytotherapy
Previous Article in Special Issue
Event-Based Path-Planning and Path-Following in Unknown Environments for Underactuated Autonomous Underwater Vehicles
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Social and Robust Navigation for Indoor Robots Based on Object Semantic Grid and Topological Map

Robotics Institute, Beihang University, Beijing 100191, China
*
Author to whom correspondence should be addressed.
Appl. Sci. 2020, 10(24), 8991; https://doi.org/10.3390/app10248991
Submission received: 16 November 2020 / Revised: 11 December 2020 / Accepted: 13 December 2020 / Published: 16 December 2020
(This article belongs to the Special Issue Advances in Robot Path Planning)

Abstract

:
For the indoor navigation of service robots, human–robot interaction and adapting to the environment still need to be strengthened, including determining the navigation goal socially, improving the success rate of passing doors, and optimizing the path planning efficiency. This paper proposes an indoor navigation system based on object semantic grid and topological map, to optimize the above problems. First, natural language is used as a human–robot interaction form, from which the target room, object, and spatial relationship can be extracted by using speech recognition and word segmentation. Then, the robot selects the goal point from the target space by object affordance theory. To improve the navigation success rate and safety, we generate auxiliary navigation points on both sides of the door to correct the robot trajectory. Furthermore, based on the topological map and auxiliary navigation points, the global path is segmented into each topological area. The path planning algorithm is carried on respectively in every room, which significantly improves the navigation efficiency. This system has demonstrated to support autonomous navigation based on language interaction and significantly improve the safety, efficiency, and robustness of indoor robot navigation. Our system has been successfully tested in real domestic environments.

1. Introduction

Robotics, as a frontier field of technology, has profoundly affected all aspects of society. Various types of indoor service robots work in human life, such as nanny robots [1] that help the disabled or patients in their daily lives, medical robots [2] that assist the elderly in cognitive activities, guide robots [3] that lead tourists or clients, and the security robots [4] that defend the security. In order to ensure the indoor robots to complete different tasks and move autonomously, it is necessary to ensure the high safety, robustness, and natural human–robot interaction of the navigation system. Although the current robot navigation system has been greatly developed, there are still two critical problems: simple and social selection of navigation goal, efficient and secure path planning.
Selection of navigation goal: The shortcomings of navigation goal selection for indoor robots are the operational complexity and goal point against the social norms. For example, the user is required to click the screen to choose a goal point in the robot operating system (ROS) [5], or set the target point in advance during the mapping [6]. Both of them are contrary to human nature of interacting with robots in natural language, because ordinary users do not have the theoretical knowledge related to robotics. In this contest, Landsiedel et al. [7] pointed out that natural language is arguably the most common and natural communication channel used and understood by humans, and dialogue systems are an integral part of modern approaches to reduce the user’s operating requirements and enhance the user’s interactive experience. Based on this, Tellex et al. [8] created a database for the robot’s behavior and corresponded to natural language so that the navigation plan can be inferred from natural language instructions. Likely, Matuszek et al. [9] created the parsers based on voice commands and corresponded control expressions. Meanwhile, great progress has been made in natural language processing, including speech recognition, semantic understanding of specific scenes, etc. The iFLYTEK [10] and Baidu [11] speech recognition products, and Jieba word segmentation algorithm [12] have been available. They help us extract phrases from natural languages. Furthermore, considering the navigation goal points should be in line with social norms, Kostavelis et al. [13] thought semantic map provides an abstraction of space and a means for human–robot communication. On the other hand, interactive robots must be equipped with environment representations and reasoning methods [7]. Rios-Martinez et al. [14] provided us with the goal area selection strategy by dividing the object surrounding space into the affordance space (the space related to human activities) and nonaffordance space (the space irrelated to human activities). The authors of [15,16] showed how to extract spatial descriptions and other spatial information from occupied grid map in human–robot conversations. Then Galindo et al. [17] integrated the hierarchical spatial information and semantic knowledge to extend the planner’s capabilities. There is still a huge promotion space of the sociality and convenience of navigation goal selection.
Passing through narrow doors: For the indoor environment, the robot’s navigation paths often pass through narrow doors. Due to sensor noise and calibration errors in real environment, it is a likelihood that the path planner fails to perceive the valid path even if the feasible path exists. On the other hand, considering the deviation of positioning and motor control, path planners do not guarantee the greatest passing door safety, leading to potential security risks, such as collision and overturn. A series of studies have been conducted on the door detection to solve this problem. Salaris et al. [18] planned a route with a confocal curve (hyperbola, ellipse, and circle) to pass the door. In [19], Aude et al. built a new door status recognition system to determine the valid path. The similar low-cost navigation system was also proposed by Kim et al. [20]. The above methods all detect the door’s position and re-plan the trajectory of crossing the door, but they are performed on-the-fly during robot navigation and waste much calculation time. Furthermore, the robotics trajectory’s safety was considered and integrated into navigation. Dai et al. [21] controlled the robot to cross the door vertically by the adaptive controller. Considering that the waypoints can greatly improve the navigation success rate and robustness, Moreno et al. [22] proposed an automatic procedure to insert auxiliary navigation points within the problematic areas, which significantly improves the security and efficiency. The authors of [23,24] used offline methods to establish a topological map of the indoor critical areas, realizing the smooth connection between navigation tasks. The efficiency was improved regarding the offline mapping. However, they still do not consider the safety of the trajectory of crossing door.
Global Path planning: Global Path planning for indoor mobile robot navigation is a wide problem, and there exist many methods and algorithms. Dijkstra [25] and A* [26] are commonly implemented and tested in global path planning. The Dijkstra traverses cells in ascending order of the length from the start and calculate the optimal path, but it is very inefficient. A* add heuristic distance to the Dijkstra’s cost algorithm, which provides the search direction pointing to goal point. Therefore, A* is more efficient and compute fewer potentials. However, heuristic does not take the room topology information into account, so there is a higher probability for A* to search in the wrong direction, and cause large computational time and low navigation speed. To improve the efficiency of A* global path planning, further modifications were conducted. Duchon et al. [27] tested various modifications of A* algorithm, including Basic, Theta*, Phi*, RSR, and JPS. RRTs algorithm [28], a technique for generating open-loop trajectories of non-linear systems with state constraints, was also applied to path planning of mobile robot. Bruce et al. [29] introduced two new extensions based on the existing RRT work, namely, waypoint cache and adaptive cost search; Melchior et al. [30] proposed particle RRT algorithm and explicitly considers the uncertainty in its domain, similar to the operation of particle filters. Although RRTs effectively improve the navigation efficiency, the path is generally not optimal and usually has corners. On the other hand, people tried to integrate the grid maps and topological maps in the mobile robot navigation. Thrun et al. [31] integrated both maps, partitioned the topological maps into coherent regions and gained better navigation efficiency. Kuipers et al. [32] combined the details of metrical maps in small-scale space with the conciseness of topological maps in large-scale space. Both of the above methods implemented the advantages of the topological maps in the complex and large environments. Then Martin et al. [33] used AI planning to carry out topological navigation in a complex indoor environment, to perform a sequence of navigation actions. It divided the navigation tasks into phases but ignored the grid maps and took a lot of time defining navigation action libraries.
This paper proposes an indoor robot navigation system with object semantic grid and topological map, which enables robot navigation to automatically select goals and become more safe, robust, and efficient. First, based on the team’s previous work [34,35], the object semantic grid and topological map are built for the indoor environment. The map contains all objects’ semantic information, occupied area, the semantic information of surrounding area. Moreover, it contains the coordinates of all door endpoints and the room dominant direction. Then, the natural language is used for human–robot interaction. The robot will extract the target room, object, and spatial relationship from the voice instructions and selects the navigation goal from the corresponding goal space. Therefore, navigation goal selection can be more convenient and social. Next, to improve the success rate and safety of navigation, we use the coordinate of door endpoints and dominant direction to generate the auxiliary navigation points (ANPs) on both sides of the door. The ANPs are used to correct the navigation trajectory, so robot crosses the door vertically. In particular, the generation of ANPs is offline. Finally, based on the ANPs and semantic topological map, global path planning is separated into each topological area and conducted respectively. This provides the correct heuristic direction for global path planning and greatly improves efficiency. Moreover, we verified our system in two real environments and three types of robots. The results show that the system is efficient, robust, and secure.
In summary, the contributions of our work are as follows:
  • We propose the indoor robot navigation system based on object semantic grid and topological map.
  • We use natural language as human–robot interaction form and realize the autonomous and social selection of navigation goal point.
  • We generate auxiliary navigation points on both sides of the door to improve the success rate of the crossing door and navigation.
  • We separate the global path planning into each topology area based on the ANPs and topological map, which improves the efficiency of the navigation system.
  • We verify our proposed system in the real office and home environments.
The remainder of this paper is organized as follows. The system overview is introduced in Section 2. The object semantic grid and topological map is introduced in Section 3. The automatic selection of navigation goal is detailed in Section 4. Section 5 presents the generation of ANPs and the algorithm of segmented global path planning. Section 6 presents the experimental results and discussion. Finally, Section 7 concludes this paper.

2. System Overview

The schematic representation of the proposed system is shown in Figure 1. It can be divided into two major modules: (1) automatic selection of navigation goal; (2) segmented global path planning. The first module is used to select a navigation goal based on human–robot speech interaction and affordance theory. The second module is used to generate ANPs and segment the global path planning into each topological area.
First, object semantic grid map and semantic topological map are built for the indoor environment. Semantic topological map can provide the rooms’ semantic information and topological information. Object semantic grid map contains the objects’ semantic information, occupied space, and semantic information of object surrounding space (affordance and nonaffordance space). Then, using the users’ natural language as input, the system runs speech recognition and word segmentation to obtain the navigation goal’s room, object, and spatial relationship (front or beside). By querying object semantic grid map and semantic topological map, the location of the target home and object can be determined. Next, according to the target spatial relationship, robot will choose affordance or nonaffordance space as the goal space and select a point from it as the navigation goal point. The orientation of navigation goal, points to the coordinate of the target object. Afterward, to improve the navigation success rate and decrease the effects of sensor noise, localization error, and motion error, we use the coordinates of the door endpoint and the dominant direction of the room, which are generated in the process of building the topological map, to generate auxiliary navigation points (ANPs) on both sides of the door. ANPs can be used to correct the robot’s trajectory through door. Finally, to improve the efficiency of global path planning, we carry on topological path planning in the topological map and get the global topological path. We segment the global path into each topological area and run path planning respectively by using ANPs as the end of every part of the global path.
In additional, considering that theories for local path planning is already achieved, we directly adopt dynamic window approach algorithm [36] to create the kinematic trajectory and focus on the automatic selection of navigation goal and segmented global path planning.

3. Object Semantic Grid and Topological Map

To select navigation goal automatically and perform segmented global path planning, it is essential to add semantic information to the traditional occupied grid map. Based on our previous work [34,35], object semantic grid map and topological map are built for indoor environment, which store: (1) object semantic information, (2) object occupied space, (3) object goal space (semantic information of object surrounding space), and (4) semantic topological information of room.
First, the object semantic grid map is built. In the instance of the alma scene [37], we create point cloud with semantic information to represent the types of objects (point clouds with different colors in Figure 2a mean different types of objects). Then, we calculate the minimum bounding rectangle of every point clouds (shown as the blue rectangles in Figure 2a) to represent the object occupied space. Next, to represent the object goal space, the object surrounding space is divided into affordance space (the space related to human activities) and nonaffordance space (the space irrelevant to human activities) according to the definition of [14], as shown in Figure 2b. The spatial relationship of object goal space and object occupied space is shown in Figure 2c. Finally, we create the semantic topological information, as shown in Figure 2d, by connected domain analysis and Bayesian analysis. In this process, the room’s main direction and the coordinates of the door endpoints are also extracted and saved in the map.

4. Automatic Selection of Navigation Goal with Speech Interaction

Natural language is the most common and social communication channel, so it is essential to enable the human–robot interaction via natural language to reduce the operation requirements to users. As shown in Figure 1, the automatic selection of navigation goal needs three inputs: natural language, object semantic grid map, and semantic topological map. The algorithm includes speech recognition, word segmentation, keyword extraction, concept query, goal space selection, and goal point selection, as shown in Algorithm A1 in Appendix A.
Before the navigation, users issue voice instructions to the robot in the form of natural language, such as “go to the front of fridge in the kitchen” including room, object, and location information. First, the language instruction is converted into text through speech recognition, and the text is broken down into phrases through Chinese word segmentation module. For example, by implementing the Jieba algorithm [12], the sentence “go to the front of fridge in the kitchen” is broken into “go to the/side/of/fridge/in the/kitchen”, as shown in Figure 3a. Since the purpose of keyword extraction is to extract phrases related to navigation goal, we build a database of phrases and their corresponding navigation behavior. Then we query the database for each phrase extracted from voice instruction, so as to determine the target room, target object, and target spatial relationship. For example, in the case of Figure 3a, the target room is the kitchen, target object is the fridge, and target spatial relationship is the side.
To make sure whether navigation goal exists in the indoor environment, we need to carry out concept query in the map, which means looking for the target room and target object in the room lists and object lists saved in the object semantic grid and topological map, as shown in Figure 3b. If target exists, the navigation path will be planned. We visualize the target room and target object in the map, as shown in Figure 3c.
To make the selection of robot target points more in line with social norms, we need to select the goal space from the object surrounding area, according to target spatial relationship. Based on [14], we divide the object surrounding area into affordance space and nonaffordance space. The affordance space refers to the area related to human activities (the front and yellow area of the object occupied area in Figure 3d), and the nonaffordance space refers to the area irrelevant to human activities (the diagonal and red area of the object occupied area in Figure 3d). In this context, nonaffordance space can be determined as goal space because the target spatial relationship is the side.
Moreover, it is necessary to filter the target points in the target area. The selection criteria are as follows. (1) Hard constraint: the target point should not be in the inflation area of cost map; (2) Soft constraint: the target point should avoid being in the other objects’ affordance space. Among two criteria, the hard constraint is absolutely inviolate, while the soft constraint should be followed as far as possible. Thus, the navigation goal point (indicated by the black point in Figure 3e) is selected from the nonaffordance space, and the orientation (indicated by the green arrow in the Figure 3f) points to the coordinate of the target object.

5. Segmented Global Path Planning

In indoor navigation, doors do have special significance. The door area is the connection area of the different topological areas, and is inevitable for robot navigation path. Thus, it is necessary to use the door area as the intermediate guidance in indoor navigation algorithm. On the other hand, the door area is usually a narrow channel with a corner, so it is a high-danger area where robot navigation fails. Therefore, this paper proposes a segmented global path planning method with the topological map and auxiliary navigation points (ANPs) to overcome the above two problems.

5.1. Door and Auxiliary Navigation Point

The door area is a high-risk area for navigation failure. Firstly, the feasible road is blocked by the wrong obstacles (shown as the dots in the red circle in Figure 4a) because of the sensor noise and calibration error, so that robot cannot correctly perceive the environment. Secondly, the shortest path through the door is usually a circle trajectory (red line in Figure 4a), so the motor and control errors like drift or slippage easily lead to the collision between the robot and the door frame.
For the first problem of sensor error, we can find that the noise can be cleared when robot directly stand in front of the door to perceive the environment (as shown in Figure 4b), so as to plan a correct path correctly. For the second problem, it is obvious that controlling the robot to cross the door along the center line of the door area, can ensure the maximum distance between the robot and the door frame to ensure the maximum safety. Therefore, we propose to use the dominant direction of the room and the coordinates of the door endpoints to generate ANPs on both sides of the door and modify the robot’s path to pass through the ANPs. This greatly improves the safety and success rate of the robot crossing door. The specific algorithm is described in Algorithm A2 in Appendix A.
In the process of building the semantic topological map based on the previous work [35], the semantic information of rooms (Room1 and Room2), dominant directions of the room (L), and coordinates of the door endpoint (E1 and E2) have been generated, as shown in Figure 5a. Then, we make the perpendicular line A1A2 through the midpoint O of line-segment E1E2, as shown in Figure 5b. Note that the length of OA1 and OA2 both are equal to ΔD and is related to door width and robotic size. A1 and A2 are used as the ANPs on both sides of the door. Furthermore, the room’s semantic information is stored in the ANP, as the form of the room which ANP is in, the room which ANP connects to. Additionally, the orientation of ANPs are parallel to L but change with navigation directions. For example, in Figure 5c,d, the orientation is up when the robot trajectory is bottom-up, and it is down when the robot trajectory is top-down.

5.2. Path Planning Algorithm

A* algorithm is one of the most widely applied algorithms in global path planning in the indoor environment. As a heuristic algorithm, it uses both of shortest path and heuristic searching, so the cell in the grid map is computed by the value:
f(n) = g(n) + h(n),
where g(n) is the length of the path from the start cell to the current cell through the selected sequence of cells, and h(n) is the heuristic distance from current cell to the goal. Heuristic provides the search direction pointing to the goal point. However, it does not take the room topological information into account, so there is a serious risk that A* provides the wrong search direction, which leads to large computational time and inefficient navigation, as shown in Figure 6a. Obviously, the map of the indoor environment (Map) is composed of multiple maps of different rooms (Mapi):
Map = ΣMapi,
and the robot must pass through the door when it moves from one room to another. Therefore, we propose to separate the global path into each topological area and use the APNs on both sides of the door as the endpoint of every path to run the path planning respectively, as described in Algorithm A3 in Appendix A. In this context, the heuristic can provide a more accurate search direction.
To obtain the sequence of room passed when robot move from the start point to the goal point, we carry on topological path planning based on the topological map, as shown in Figure 6b. The red dotted line represents the topological path.
Thus, the robot will pass through room B, room D, and room E, which are stored in the room sequence. We infer the corresponding ANPs sequence from the room sequence, and then the global path is segmented into five parts. In Figure 6c, blue dots indicate the ANPs sequence, and the red dotted line indicates the global path. Figure 6d–h shows the results of every path planning and their traversed cells. Through calculation, the number of traversed cells of A* is 30,571, while the number of our method is 1694. The decrease is 94.46%. It is found that our method provides a more accurate search direction for path planning in each topological area by using ANPs and greatly reduces the traversed cells and computational time.

6. Experimental Results

6.1. Experimental Setup

6.1.1. Experimental Platform

For the verification of our system, we selected three experimental platforms of different radius. Figure 7 shows the configurations of these robots. All of them are equipped with Kobuki, Hokuyo UST-10LX 2D lidar sensor, Kinect V2 RGB-D camera, and Hasee z7m-kp7gc laptop whose CPU is Intel i7-8750h, GPU is gtx1050ti, RAM is 12 GB. All of their shapes are circular, and the max radiuses are 0.18 m, 0.23 m and 0.28 m respectively, as shown in Figure 7.
The navigation algorithm is based the robot operating system (ROS), which provides various libraries and tools to help create robot application. The robot pose was estimated by using AMCL [38], the ROS implementation of the Monte Carlo localization algorithm [39], which is feed the laser measurement data and odometry data and resample the particles representing the belief of robot pose. For the controllers and algorithms for controlling the robot, the ROS move_base stack [40] is implemented, with segmented global path planning and dwa local path planning. The former segments the global path into every topological area based on topological map, and run Astar path planning, respectively. The latter provides the controller that drives a robot in the plane, by assessing every local paths’ costs of traversing through the grid cells and determine the linear and angular velocity to send to the robot. Meanwhile, ROS move_base stack provides the global cost map and local cost map [41]. We configured the 2D costmap with the static layer (the unchanging portion of the costmap generated by SLAM), the obstacle layer (the obstacles created by the sensor data), and the inflation layer (the inflation of the obstacles to represent the configuration space of the robot and avoid the collision).

6.1.2. Experimental Environment

The experimental environments include home and office. The home environment includes one bathroom, two bedrooms, one kitchen, and one living room. All doors are 0.74 m wide. Moreover, according to the result of semantic segmentation algorithm, there are 11 objects in the home environment. For the convenience of the experiment, we select five objects as the endpoints of the navigation paths, and they are sink in bathroom, bed in master bedroom, bed in second bedroom, TV in living room, and fridge in kitchen, as shown in Figure 8a. Figure 8c is the object semantic grid and topological map established for the home environment, which contains: object semantic information, object occupied space, object goal space (affordance and nonaffordance space), semantic topological information of room, the room dominant direction, and the coordinates of door endpoints. Figure 8e visualizes the door endpoints in the home map, which is the intermediate product of generating the semantic topology map based on [35].
Similarly, the office environment includes one meeting room, one laboratory, one corridor, and one elevator hall. The door width in the environment is 0.65–0.96 m. There are 12 objects in the environment, and we select 5 objects as the endpoints of navigation paths, which are notebook in meeting room, desk, and microwave in laboratory, desk in elevator hall, and desk in corridor, as shown in Figure 8b. Figure 8d shows the object semantic grid and topological map of office environment. Figure 8f visualizes the door endpoints in the office map (which is cut and rotate by 90 degrees).

6.2. Automatically Selecting Navigation Goal Results

This paper proposed the autonomous and social selection of navigation goal through natural language interaction and the object semantic grid and topological map. To verify the ability to select goal autonomously by language interaction, the experiment was designed as follows:
The operator designated the navigation target by language instructions containing the target home, object, and spatial relationship. Twenty paths were set in the home environment (as shown in Table 1) and 18 paths in the office environment (as shown in Table 2). Especially, both of the front space and side space of every object are set as the goal space at least twice. If the value of cell (i, j) in the table is 1, the voice command is to move from object i to the front of object j, and then the robot will select a navigation point from the affordance space of object j. If the value is 2, the voice instruction is to move from object i to the side of object j, and then the robot will select a navigation point from the nonaffordance space of object j. In addition, the robot radius was set 0.18 m, and path planning algorithm and controller were set by default, so that the experiment focused on autonomously select goal by language interaction.
Only parts of environmental results are illustrated in Table 3 due to space limitations. As shown in the column called “word segmentation”, the target information are extracted from voice instructions (which is Chinese originally and translated into English). The coordinate of navigation goal point selected is shown in the column called “target point selection” and all of these pictures are generated by the RVIZ software during the navigation. The red rectangle is the nonaffordance space, the green rectangle is the affordance space, and the blue arrow is the goal pose. The navigation results are shown in the column called “Navigation Result”. The human operator is also shown in the pictures to indicate whether the robot’s final position satisfies the requirement of the human–robot coexisting environment.
Multiple conclusions can be extracted from these results:
  • The target information, including target room, object, and spatial relationship, can be extracted accurately and clearly through language reorganization [10], word segmentation [12], keyword extraction, and concept query. For example, the command in the first row of Table 3 “go to the front of the sink in the bathroom” can be divided into “go to the/front/of the/sink/in the/bathroom “, in which the target room is bathroom, target object is sink, and target spatial relationship is front.
  • The navigation goal is selected automatically and correctly, and it is excellent in terms of social norms and the object affordance theory through qualitative comparison. The goal is located in the affordance space if goal spatial relationship is front, while it is located in the nonaffordance space if goal spatial relationship is side. In addition, the goal location satisfies the hard constraint (not in the inflation area of cost map) and soft constraint (avoid other objects’ affordance space) as described in Section 3.
  • The system helps the robot better integrated into the human–robot coexisting environment according to the navigation results. When the robot wants to operate the target object, such as the TV in the third row or the laptop in the sixth row of Table 3, it can reach the position conducive to complete the operation task. When the robot doesn’t need to operate the object, it can reach the area diagonal to the object, so it will not hinder the user from operating the object, like the navigation results in the second row and fourth row of Table 3.

6.3. Segmented Global Path Planning Results

The segmented global path planning method with topological map and auxiliary navigation points aims to improve the success rate and safety of domestic navigation and decrease the computational time. The experiments were grouped into the test on the success rate and the test on global path planning efficiency to evaluate the method.
To compare the performance of the success rate, the crossing door success rate (CDSR) and navigation success rate (NSR) was employed as standard. The CDSR indicates the door number passed successfully divided by the total door number. If the robot collides with the door frame or cannot plan the path in the process of passing door, it is considered that the robot fails to pass the door. Furthermore, in terms of the likelihood of collision to other obstacles leading to navigation termination, NSR is defined and indicates the number of successful navigation paths divided by the total number of navigation paths. If the robot reaches the destination and does not collide with other objects during the whole navigation process, the robot navigation is successful. The higher NSR and CDSR indicate better performance.
To assess the improvement of global path planning efficiency, we defined the path length and the traversed cells number. The shorter the planned path, the better the algorithm. To improve the efficiency of planning, the less time the algorithm consumes, the better the algorithm. In addition to considering that different computers have different performances and the time consumed mainly depends on the number of traversed cells (the cells whose potential has been calculated) by the path planning algorithm, we used the number of traversed cells to evaluate the efficiency of our system.

6.3.1. Related Parameters and ANPs

The navigation target objects we selected in the family scene were the bed in master bedroom (called bed 1), bed in second bedroom (called bed 2), fridge in kitchen, and sink in bathroom (as shown in Figure 8a), all of which are distributed across various topological areas and at least two doors between them. The robot was ordered from one object to another objects in different rooms. Therefore, there were 12 paths in total: bed 1 ↔ bed 2, bed 1 ↔ fridge, bed 1 ↔ sink, bed 2 ↔ fridge, bed 2 ↔ sink, and fridge ↔ sink. The ANPs of the home scene, generated by Algorithm A2 in Appendix A, are shown in Figure 9a.
Similarly, the navigation target objects we selected from the office environment were the desk (called desk 1) and the microwave in lab, the laptop in the meeting room, the desk in the elevator hall (called desk 2), and the desk in the corridor (called desk 3), as shown in Figure 8b. There were 18 paths in total: desk 1 ↔ desk 2, desk 1 ↔ desk 3, desk 1 ↔ laptop, desk 2 ↔ desk 3, desk 2 ↔ microwave, desk 2 ↔ laptop, desk 3 ↔ microwave, desk 3 ↔ laptop, microwave ↔ laptop. The APNs of the office scene are shown in Figure 9b.
In order to evaluate different robot dimensions, we designated three platforms with different diameters shown in Figure 7. The robot radius employed in the home scene were 0.18 m, 0.23 m, and 0.28 m, while the radius employed in the office scene is 0.18 m and 0.23 m.

6.3.2. Success Rate

Table 4 and Table 5 respectively summarize the experimental results of the CDSR and NSR with different radius in the home scene and the office scene. In the experiment, the ROS move_base stack [40] with A* global planner and DWA local planner were implemented to compare with the segmented global path planning method.
Multiple conclusions can be extracted from these results:
  • The proposed navigation algorithm based on the ANPs can significantly improve crossing door success rate and navigation success rate for the three robot sizes and two environments, reaching improvements of up to 33.33% (e.g., see 0.23 m radius in the home scene) and 50% (e.g., see 0.23 m radius in the office scene).
  • The first reason for the increase of success rate is that the proposed method can eliminate the influence of observation error on the navigation. In the process of approaching the door, the erroneous obstacle completely obstructed the feasible area crossing door, and the valid path could not be planned, thus giving up navigation. As shown in Figure 10a, when the robot with a radius of 0.23 m approached the bathroom’s door (indicated in the red circle), the lidar observation data had noise, making the door area blocked by obstacles. Figure 10b shows our proposed method in the same scenarios. First, the robot was controlled to the auxiliary navigation point (the position where robot stands in Figure 10b) and observed the door area in the direction parallel to the trajectory passing direction. Thus, the shape of the door area was captured successfully. Figure 10c,d show the similar results of going to the laptop in the meeting room based on ROS move_base and our proposed algorithm when the robot was in the office environment with the radius of 0.23 m.
  • The second reason for the increase of success rate is that, by setting ANPs on both sides of the door, the robot passes through the door in an approximately straight line, reducing the probability of collision. In the indoor scene, the connection channels of different topological areas are usually the right angle. For example, 20 of the 30 paths in our experiment’s home and office scenes were the right angle. By observing the move_base navigation trajectory (expressed by red line in Figure 10a,c), it can be seen that the crossing door trajectory is circular-like. This makes the distance between the two sides of the robot and the obstacle uneven and increases the probability of collision. The proposed method forces the robot to pass through the door along the door area’s centerline, keeping the maximum distance from the obstacle on both sides, so as to improve the success rate and security.
  • As the robot’s radius increases, both of the success rates of our method and move_base are degraded. The increase in the robot’s radius narrows the feasible area when passing the door, so it is more likely that the valid path cannot be sensed or the collision occurs. For example, the door’s width in the home scene was 0.74 m, and as the diameter of the robot increased, the feasible area for the robot to pass the door gradually decreased, respectively 0.34 m, 0.24 m, and 0.14 m.

6.3.3. Global Path Planning Efficiency

Table 6 and Table 7 shows the global path planning results for robots of different sizes in home and office environments. Considering that A* and Dijkstra were successfully implemented and tested as the path planning algorithms for mobile robots, we employed A* and Dijkstra to compare with our proposed segmented global path planning algorithm.
Multiple conclusions can be extracted from these results:
  • Compared with A* and Dijkstra, the segmented global path planning algorithm greatly reduced the number of traversed cells for the three robot sizes and two environments, reaching a decrease of up to 76.29% (e.g., see 0.18 m radius in the office scene) and 94.54% (e.g., see 0.23 m radius in the office scene).
  • The reason why the proposed method improves the navigation efficiency is that the correct heuristic direction pointing to ANPs is generated by segmented global path planning. However, the heuristic direction of A* method and segmented global path planning both are correct and similar for the simple and no branching path. In these scenarios, the improvements of segmented global path planning compared to A*, are not obvious or even negative. For example, there were three paths in the home environment: bed in master room to sink, bed in master room to fridge, fridge to sink, whose results of traversed cells of A* are shown in Figure 11. It can be seen that the heuristic search direction of A* was approximate to the optimal search direction. Specifically, our method forced the robot navigation path to pass through the ANPs, leading to a slightly or negative improvement compared with A*.
  • The increase of navigation efficiency by our method is more significant in the scene with large areas and complex plane structure. Comparing the two scenes’ experimental data, the reduction of traversed cell numbers was larger in the office scene (up to 30.20% and 85.86% in the home scenario, while 73.68% and 94.54% in the office scenario). There were two doors, and the arrangement of things was more disorderly and scattered in the Lab. So, it was more likely for A* to provide wrong heuristic search directions, resulting in inefficiency cell traversal and large computational time. Simultaneously, the two environments’ door areas were approximately the same size, while the topological area of the office was larger. It is inferred that the segmented global path planning method contributes more to navigation efficiency in the broad and complex scene.
  • In terms of path length, the path planned by our method was slightly longer than that of A* and Dijkstra, with an average of 6.42% and 6.25%. This is because the navigation trajectory by our method was forced to pass through the ANPs to improve the success rate and safety of domestic navigation, while the trajectory by A* or Dijkstra algorithm kept close to the obstacle for the shortest length.

7. Conclusions

This paper proposes a social and robust indoor robot navigation system based on object semantic grid and topological map, which combines the two major modules: automatic selection of navigation goal and segmented global path planning. The proposed method aims at addressing the three critical problems. First, to select navigation goal more conveniently and socially, natural language is used as the human–robot interaction form, from which the target room, object, and spatial relationship can be extracted through speech recognition and word segmentation technology. Thus, the robot determines the target space and selects the navigation goal point from it. For example, we can get the target room “meeting room,” the target object “laptop,” and the target space decided as nonaffordance space, from the voice instruction “go to the side of laptop in the meeting room.” Furthermore, to improve the success rate and security of indoor navigation, we use the door endpoint coordinates and the room dominant direction kept in the topological map, to generate auxiliary navigation points on both sides of the door, to correct the robot trajectory. Finally, to improve the efficiency of global path planning, we segment the global path into every single topological space and plan the path respectively based on the auxiliary navigation points. The system is tested by a series of experiments in real indoor environments with multiple robot dimensions. Experimental results show that the navigation goals satisfy the social rules better. Auxiliary navigation point significantly improves the crossing door success rate (average 24.22%) and navigation success rate (average 30.56%) compared to ROS move_base. The number of traversed cells is greatly reduced than A* (average 69.85%) and Dijkstra (average 93.25%), especially in the complex and large-scale environment.
In future work, we will improve the system and exploit deeply the ability of environment expression and reasoning, such as more associations between voice instructions and spatial relationships, so that system can be more diverse and social. At the same time, the navigation in the multi-connected topology area will also be considered by imposing the distance constraints and social constraints.

Author Contributions

Conceptualization, J.Z. and W.W.; methodology, J.Z.; software, J.Z.; validation, J.Z., X.Q., and Z.L.; formal analysis, J.Z., X.Q., and Z.L.; investigation, J.Z.; resources, W.W.; data curation, J.Z. and X.Q.; writing—original draft preparation, J.Z.; writing—review and editing, J.Z. and W.W.; visualization, J.Z.; supervision, W.W.; project administration, J.Z.; funding acquisition, W.W. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the Natural Science Foundation of China under grant number 91748101 and the National Key Research and Development Program of China under grant number 2020YFB1313600.

Conflicts of Interest

The authors declare no conflict of interest.

Appendix A

Algorithm A1: Automatic selection of navigation goal
Data: voice instruction: V; semantic topological map STM; object semantic grid map: OSGM;
Result: GoalCoordinate;
1: Home goal, object goal, location goal ← speech recognition and word segmentation (V).
2: Home lists ← read from STM.
3: Object lists, AffordanceSpace, NonaffordanceSpace ← read from OSGM.
4: if(Home goal ∈ Home lists && object goal ∈ object lists)  //concept query
5: if(location goal = front)
6:  GoalCoordinate.point ← select illegal point from AffordanceSpace.
7:  GoalCoordinate. orientation ← direction to object.
8: else if(location goal = side)
9:  GoalCoordinate.point ← select illegal point from NonaffordanceSpace.
10:  GoalCoordinate. orientation ← direction to object.
11:  endif
12: endif
Algorithm A2: Generation of ANPs
Data: Coordinates of the door endpoint: {E1, E2}; Pair of topological area: {Room1, Room2}; distance: Δd.
Result: ANPs: A1 and A2
1: O ← (E1 + E2)/2
2: Line ← E1 x E2    //line passing through E1, E2
3: d ← [1, line(1)/line(0)]   //perpendicular line’s director vector
4: A1.position ← O + △d · d
5: A1.position ← {room1, room2}
6: A2.position ← O-△d · d
7: A2.position ← {room2, room1}
Algorithm A3: Segmented global path planning
Data: Sequence of ANPs: ANPs; Topological map: TM; Goal point; Start point.
Result: Navigation goal sequence: Goals.
1: RoomStart ← topological area where Start point exists in the TM.
2: RoomEnd ← topological area where Goal point exists in the TM.
3: Topological Path ← topological path planning from RoomStart to RoomEnd.
4: Room Sequence ← all rooms in sequence from Topological Path.
5: Goals ← all auxiliary navigation points according to Rome Sequence.
6: Goals ← Goal point.

References

  1. Song, W.K.; Song, W.J.; Kim, Y.; Kim, J. Usability test of KNRC self-feeding robot. IEEE Int. Conf. Rehabil. Robot. 2013, 1–5. [Google Scholar] [CrossRef]
  2. Bemelmans, R.; Gelderblom, G.J.; Jonker, P.; de Witte, L. Socially assistive robots in elderly care: A systematic review into effects and effectiveness. J. Am. Med. Dir. Assoc. 2012, 13, 112–114. [Google Scholar] [CrossRef] [PubMed]
  3. Kanda, T.; Shiomi, M.; Miyashita, Z.; Ishiguro, H.; Hagita, N. An affective guide robot in a shopping mall. In Proceedings of the 4th ACM/IEEE International Conference on Human-Robot Interaction, HRI’09, La Jolla, CA, USA, 11–13 March 2009. [Google Scholar]
  4. Salman, R.; Willms, I. A mobile security robot equipped with UWB-radar for super-resolution indoor positioning and localisation applications. In Proceedings of the 2012 International Conference on Indoor Positioning and Indoor Navigation, IPIN 2012—Conference Proceedings, Sydney, Australia, 13–15 November 2012. [Google Scholar]
  5. Robot Operating System. Available online: http://wiki.ros.org/ (accessed on 11 November 2020).
  6. Qi, X.; Wang, W.; Guo, L.; Li, M.; Zhang, X.; Wei, R. Building a Plutchik’s Wheel Inspired Affective Model for Social Robots. J. Bionic Eng. 2019. [Google Scholar] [CrossRef]
  7. Landsiedel, C.; Rieser, V.; Walter, M.; Wollherr, D. A review of spatial reasoning and interaction for real-world robotics. Adv. Robot. 2017. [Google Scholar] [CrossRef]
  8. Tellex, S.; Kollar, T.; Dickerson, S.; Walter, M.R.; Banerjee, A.G.; Teller, S.; Roy, N. Understanding natural language commands for robotic navigation and mobile manipulation. In Proceedings of the National Conference on Artificial Intelligence, San Francisco, CA, USA, 7–11 August 2011. [Google Scholar]
  9. Matuszek, C.; Herbst, E.; Zettlemoyer, L.; Fox, D. Learning to Parse Natural Language Commands to a Robot Control System. In Experimental Robotics; Springer: Heidelberg, Germany, 2013; pp. 403–415. [Google Scholar]
  10. Xu, Y.; Song, Y.; Long, Y.H.; Zhong, H.B.; Dai, L.R. The description of iFlyTek Speech Lab system for NIST2009 language recognition evaluation. In Proceedings of the 2010 7th International Symposium on Chinese Spoken Language Processing, ISCSLP 2010—Proceedings, Tainan, Taiwan, 29 November–3 December 2010. [Google Scholar]
  11. Baidu AI Open Platform. Available online: https://ai.baidu.com/ (accessed on 11 November 2020).
  12. Jieba Chinese Text Segmentation. Available online: https://github.com/fxsjy/jieba/ (accessed on 11 November 2020).
  13. Kostavelis, I.; Gasteratos, A. Semantic mapping for mobile robotics tasks: A survey. Robot. Auton. Syst. 2015. [Google Scholar] [CrossRef]
  14. Rios-Martinez, J.; Spalanzani, A.; Laugier, C. From Proxemics Theory to Socially-Aware Navigation: A Survey. Int. J. Soc. Robot. 2015. [Google Scholar] [CrossRef]
  15. Skubic, M.; Perzanowski, D.; Blisard, S.; Schultz, A.; Adams, W.; Bugajska, M.; Brock, D. Spatial language for human-robot dialogs. IEEE Trans. Syst. Man Cybern. Part C Appl. Rev. 2004. [Google Scholar] [CrossRef]
  16. Skubic, M.; Perzanowski, D.; Schultz, A.; Adams, W. Using spatial language in a human-robot dialog. In Proceedings of the 2002 IEEE International Conference on Robotics and Automation (Cat. No.02CH37292), Washington, DC, USA, 11–15 May 2002. [Google Scholar] [CrossRef] [Green Version]
  17. Galindo, C.; Fernández-Madrigal, J.A.; González, J.; Saffiotti, A. Robot task planning using semantic maps. Robot. Auton. Syst. 2008. [Google Scholar] [CrossRef] [Green Version]
  18. Salaris, P.; Vassallo, C.; Souères, P.; Laumond, J.P. The Geometry of Confocal Curves for Passing through a Door. IEEE Trans. Robot. 2015. [Google Scholar] [CrossRef]
  19. Aude, E.P.L.; Lopes, E.P.; Aguiar, C.S.; Martins, M.F. Door crossing and state identification using robotic vision. IFAC Proc. Vol. 2006, 39, 659–664. [Google Scholar] [CrossRef]
  20. Kim, B.K.; Tanaka, H.; Sumi, Y. Robotic wheelchair using a high accuracy visual marker LentiBar and its application to door crossing navigation. In Proceedings of the—IEEE International Conference on Robotics and Automation, Seattle, WA, USA, 26–30 May 2015. [Google Scholar]
  21. Dai, D.; Jiang, G.; Xin, J.; Gao, X.; Cui, L.; Ou, Y.; Fu, G. Detecting, locating and crossing a door for a wide indoor surveillance robot. In Proceedings of the 2013 IEEE International Conference on Robotics and Biomimetics, ROBIO 2013, Shenzhen, China, 12–14 December 2013. [Google Scholar]
  22. Moreno, F.A.; Monroy, J.; Ruiz-Sarmiento, J.R.; Galindo, C.; Gonzalez-Jimenez, J. Automatic waypoint generation to improve robot navigation through narrow spaces. Sensors 2020, 20. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  23. Tapus, A.; Ramel, G.; Dobler, L.; Siegwart, R. Topology learning and recognition using Bayesian Programming for mobile robot navigation. In Proceedings of the 2004 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS) (IEEE Cat. No.04CH37566), Sendai, Japan, 28 September–2 October 2004; Volume 4, pp. 3139–3144. [Google Scholar] [CrossRef] [Green Version]
  24. Althaus, P.; Christensen, H.I. Smooth task switching through behaviour competition. Robot. Auton. Syst. 2003, 44, 241–249. [Google Scholar] [CrossRef]
  25. Dijkstra Algorithm. Available online: https://en.wikipedia.org/wiki/Dijkstra%27s_algorithm (accessed on 11 November 2020).
  26. Bell, M.G.H. Hyperstar: A multi-path Astar algorithm for risk averse vehicle navigation. Transp. Res. Part B Methodol. 2009. [Google Scholar] [CrossRef]
  27. Duchon, F.; Babinec, A.; Kajan, M.; Beno, P.; Florek, M.; Fico, T.; Jurišica, L. Path planning with modified A star algorithm for a mobile robot. Procedia Eng. 2014, 96, 59–69. [Google Scholar] [CrossRef] [Green Version]
  28. LaValle, S.M. Rapidly-Exploring Random Trees: A New Tool for Path Planning; Computer Science Department: Troy, NY, USA, 1998. [Google Scholar]
  29. Bruce, J.; Veloso, M.M. Real-time randomized path planning for robot navigation. In Proceedings of the RoboCup 2002, Fukuoka, Japan, 19–25 June 2002; Springer: Berlin/Heidelberg, Germany. [Google Scholar]
  30. Melchior, N.A.; Simmons, R. Particle RRT for path planning with uncertainty. In Proceedings of the IEEE International Conference on Robotics and Automation, Roma, Italy, 10–14 April 2007; pp. 1617–1624. [Google Scholar]
  31. Thrun, S.; Buecken, A. Integrating grid-based and topological maps for mobile robot navigation. In Proceedings of the National Conference on Artificial Intelligence, Portland, OR, USA, 4–8 August 1996. [Google Scholar]
  32. Kuipers, B.; Modayil, J.; Beeson, P.; MacMahon, M.; Savelli, F. Local metrical and global topological maps in the hybrid Spatial Semantic Hierarchy. In Proceedings of the IEEE International Conference on Robotics and Automation, New Orleans, LA, USA, 26 April–1 May 2004. [Google Scholar]
  33. Martin, R.F.; Gines, J.; Vargas, D.; Rodraguez-Lera, F.J.; Matellan, V. Planning Topological Navigation for Complex Indoor Environments. In Proceedings of the IEEE International Conference on Intelligent Robots and Systems, Madrid, Spain, 1–5 October 2018. [Google Scholar]
  34. Qi, X.; Wang, W.; Liao, Z.; Zhang, X.; Yang, D.; Wei, R. Object semantic grid mapping with 2D LiDAR and RGB-D camera for domestic robot navigation. Appl. Sci. 2020, 10. [Google Scholar] [CrossRef]
  35. Qi, X.; Wang, W.; Zhang, X.; Liao, Z.; Li, M.; Yuan, M. Indoor topological map building with virtual door detection. J. Jilin Univ. 2020, 50. [Google Scholar] [CrossRef]
  36. Fox, D.; Burgard, W.; Thrun, S. The dynamic window approach to collision avoidance. IEEE Robot. Autom. Mag. 1997. [Google Scholar] [CrossRef] [Green Version]
  37. Ruiz-Sarmiento, J.R.; Galindo, C.; Gonzalez-Jimenez, J. Robot@Home, a robotic dataset for semantic mapping of home environments. Int. J. Robot. Res. 2017. [Google Scholar] [CrossRef] [Green Version]
  38. AMCL Reference Website. Available online: http://wiki.ros.org/amcl (accessed on 12 November 2020).
  39. Fox, D.; Burgard, W.; Dellaert, F.; Thrun, S. Monte Carlo Localization: Efficient position estimation for mobile robots. In Proceedings of the National Conference on Artificial Intelligence, Orlando, FL, USA, 18–22 July 1999. [Google Scholar]
  40. Move_Base Reference Website. Available online: http://wiki.ros.org/move_base (accessed on 12 November 2020).
  41. Costmap_2d. Available online: http://wiki.ros.org/costmap_2d (accessed on 15 November 2020).
Figure 1. System overview. The system contains two major parts: automatic selection of navigation goal and segmented global path planning.
Figure 1. System overview. The system contains two major parts: automatic selection of navigation goal and segmented global path planning.
Applsci 10 08991 g001
Figure 2. Object Semantic Grid and Topological Map. (a) Object semantic information and object occupied space. (b) Object goal space: red rectangle indicates the nonaffordance space (NAS), and the original color rectangle indicates the affordance space. (c) Spatial relationship of object goal space and object occupied space. (d) Semantic topological information.
Figure 2. Object Semantic Grid and Topological Map. (a) Object semantic information and object occupied space. (b) Object goal space: red rectangle indicates the nonaffordance space (NAS), and the original color rectangle indicates the affordance space. (c) Spatial relationship of object goal space and object occupied space. (d) Semantic topological information.
Applsci 10 08991 g002
Figure 3. Automatic selection of navigation goal: (a) Word segmentation and concept query. (b) Object semantic grid and topological map. (c) Target object and target room. (d) The affordance space and nonaffordance space of the object goal. (e) Navigation goal point. (f) Goal orientation.
Figure 3. Automatic selection of navigation goal: (a) Word segmentation and concept query. (b) Object semantic grid and topological map. (c) Target object and target room. (d) The affordance space and nonaffordance space of the object goal. (e) Navigation goal point. (f) Goal orientation.
Applsci 10 08991 g003
Figure 4. Navigation failure because of perceptual error: (a) The perceptual error in the door area results in the navigation failure. (b) Correct perceptual location can eliminate the perceptual error.
Figure 4. Navigation failure because of perceptual error: (a) The perceptual error in the door area results in the navigation failure. (b) Correct perceptual location can eliminate the perceptual error.
Applsci 10 08991 g004
Figure 5. Auxiliary navigation points. (a) Coordinates of the door endpoint, E1 and E2; dominant directions of the room, L; room semantic information, Room1 and Room2. (b) Perpendicular line A1A2. (c) Point and upward orientation. (d) Point and downward orientation.
Figure 5. Auxiliary navigation points. (a) Coordinates of the door endpoint, E1 and E2; dominant directions of the room, L; room semantic information, Room1 and Room2. (b) Perpendicular line A1A2. (c) Point and upward orientation. (d) Point and downward orientation.
Applsci 10 08991 g005
Figure 6. The comparison of A* algorithm and segmented global path planning. (a) A* algorithm. (b) Topological map: the red dotted line is the topological path. (c) auxiliary navigation points (ANPs) sequence (dh) segmented global path planning. The colorful cell means the cells traversed.
Figure 6. The comparison of A* algorithm and segmented global path planning. (a) A* algorithm. (b) Topological map: the red dotted line is the topological path. (c) auxiliary navigation points (ANPs) sequence (dh) segmented global path planning. The colorful cell means the cells traversed.
Applsci 10 08991 g006
Figure 7. Robot platform: the three lengths in the right column means different maximum robot radiuses.
Figure 7. Robot platform: the three lengths in the right column means different maximum robot radiuses.
Applsci 10 08991 g007
Figure 8. Experimental environments. (a) Room environment, (b) office environment, (c) object semantic grid and topological map of home, (d) object semantic grid and topological map of office, (e) door endpoints of home, and (f) door endpoints of office.
Figure 8. Experimental environments. (a) Room environment, (b) office environment, (c) object semantic grid and topological map of home, (d) object semantic grid and topological map of office, (e) door endpoints of home, and (f) door endpoints of office.
Applsci 10 08991 g008
Figure 9. Auxiliary Navigation Points: (a) home scene. (b) office scene.
Figure 9. Auxiliary Navigation Points: (a) home scene. (b) office scene.
Applsci 10 08991 g009
Figure 10. Generation and elimination of observation error. (a,c) Erroneous obstacle in the red circle blocks the path. (b,d) Error is eliminated when robot is at the ANP.
Figure 10. Generation and elimination of observation error. (a,c) Erroneous obstacle in the red circle blocks the path. (b,d) Error is eliminated when robot is at the ANP.
Applsci 10 08991 g010
Figure 11. Heuristic search direction of A* is approximately optimal in the specific scenarios. (a) bed in master room to sink. (b) bed in master room to refrigerator. (c) refrigerator to sink.
Figure 11. Heuristic search direction of A* is approximately optimal in the specific scenarios. (a) bed in master room to sink. (b) bed in master room to refrigerator. (c) refrigerator to sink.
Applsci 10 08991 g011
Table 1. Navigation goal in home.
Table 1. Navigation goal in home.
ObjectBed1 1Bed2 2FridgeSinkTV
bed1-1111
bed21-111
fridge11-22
sink222-2
TV2222-
1 Bed in master bedroom; 2 Bed in second bedroom.
Table 2. Navigation goal in office.
Table 2. Navigation goal in office.
ObjectDesk1 1Desk2 2Desk3 3MicrowaveLaptop
desk1-1111
desk21-111
desk311-22
microwave222-2
laptop2222-
1 Desk in laboratory; 2 Desk in elevator hall; 3 Desk in corridor.
Table 3. Experiment results of automatically selecting navigation goal.
Table 3. Experiment results of automatically selecting navigation goal.
Word SegmentationSelecting Navigation Goal 1Navigation Result
Applsci 10 08991 i001
Applsci 10 08991 i002
Applsci 10 08991 i003
Applsci 10 08991 i004
Applsci 10 08991 i005
Applsci 10 08991 i006
Applsci 10 08991 i007
1 The red rectangle is the nonaffordance space. The green rectangle is the affordance space. The blue arrow is the target pose of the robot.
Table 4. Results of crossing door success rate.
Table 4. Results of crossing door success rate.
Radius (m)NAMBTNAS (%)MBS (%)CR (%)
Home0.1824192410079.1720.83
0.2323152495.8362.533.33
0.28128245033.3316.67
Office0.1828232810082.1417.86
0.2328192810067.8632.14
Average-1158412889.8465.6324.22
NA: the crossing door number when using the proposed algorithm based on the ANPs. MB: the crossing door number when using the robot operating system (ROS) move_base stack. T: the total door number of all paths. NAS: crossing door success rate when using the proposed algorithm based on the ANPs (NA/T). MBS: crossing door success rate when using ROS move_base stack (MB/T). CR: the improvement when compared to ROS move_base (NAS-MBS). Average values are also included.
Table 5. Results of navigation success rate.
Table 5. Results of navigation success rate.
Radius (m)NAMBTNAS (%)MBS (%)CR (%)
Home0.18129121007525
0.231171291.6758.3333.33
0.28211216.678.338.33
Office0.1818131810072.2227.78
0.23189181005050
Average-61397284.7254.1630.56
NA: the number of successful navigation paths when using the proposed algorithm based on the ANPs. MB: the number of successful navigation paths when using the ROS move_base stack. T: the total number of navigation paths. NAS: navigation success rate when using the proposed algorithm based on the ANPs (NA/T). MBS: navigation success rate when using ROS move_base stack (MB/T). CR: the improvement when compared to ROS move_base (NAS-MBS). Average values are also included.
Table 6. Results of traversed cells numbers.
Table 6. Results of traversed cells numbers.
Radius (m)NAA*DJCA (%)CD (%)
Home0.18916113,12564,78230.2085.86
0.23786510,18855,55722.8085.84
0.28912212,45644,86526.7779.67
Office0.1836,404153,531631,47576.2994.24
0.2337,527142,595686,75873.6894.54
Average-100,079331,8951,483,43769.8593.25
NA: numbers when using segmented global path planning. A*: numbers when using A*. DJ: numbers when using Dijkstra. CA: increase of segmented global path planning compared to A*. CD: increase of segmented global path planning compared to Dijkstra.
Table 7. Results of path length.
Table 7. Results of path length.
Radius (m)NAA*DJCA (%)CD (%)
Home0.18146914021408−4.78−4.33
0.23134812811283−5.23−5.07
0.28147214191437−3.73−2.43
Office0.18760871367138−6.61−6.58
0.23760270847086−7.31−7.28
Average-19,49918,32218,352−6.42−6.25
NA: length when using segmented global path planning. A*: length when using A*. DJ: length when using Dijkstra. CA: increase of segmented global path planning compared to A*. CD: increase of segmented global path planning compared to Dijkstra.
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Zhang, J.; Wang, W.; Qi, X.; Liao, Z. Social and Robust Navigation for Indoor Robots Based on Object Semantic Grid and Topological Map. Appl. Sci. 2020, 10, 8991. https://doi.org/10.3390/app10248991

AMA Style

Zhang J, Wang W, Qi X, Liao Z. Social and Robust Navigation for Indoor Robots Based on Object Semantic Grid and Topological Map. Applied Sciences. 2020; 10(24):8991. https://doi.org/10.3390/app10248991

Chicago/Turabian Style

Zhang, Jiadong, Wei Wang, Xianyu Qi, and Ziwei Liao. 2020. "Social and Robust Navigation for Indoor Robots Based on Object Semantic Grid and Topological Map" Applied Sciences 10, no. 24: 8991. https://doi.org/10.3390/app10248991

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop