Manipulation planning for the entire task would alleviate the issues of global sub-optimality, but this is highly computationally intensive. Motion coordination between the mobile base and the manipulator, collision checking with the environment and self-collision checking, motion constraints are some of the added complexities that are seen in this approach.
3.2.1. General High DOF Planning
Planning algorithms that are capable of dealing with high dimensions were used for mobile manipulators where the whole system was considered as a single system despite the behavioral difference of the mobile base and the manipulator.
Brock and Kavraki [
63] calculated the free space representation as a swept volume (Tunnel) using wavefront expansion algorithm and used a local minima free potential field function to find a path through the tunnel. This method sacrificed completeness for real-time performance while guaranteeing a minimum safety distance to obstacles. This algorithm was validated on a free-floating mobile manipulator which made it applicable for holonomic wheeled mobile manipulators.
Su and Xie proposed the Representation Space (RS) in their work in [
64] which is a space spanned by the attributes of the robot system and the given task. CS and TS can be considered as subsets of RS where even a link length of a manipulator can be one of the variables in RS. The authors explicitly calculated RS (Discretized each dimension and checked for validity at each point then recorded whether the point is valid or not) and carried out motion planning using A* algorithm. In [
65], A* algorithm was used on RS where the heuristic cost was calculated as the Euclidean distance from current node to goal.
Both above algorithms calculated a representation of the free space which was computationally expensive and the representation needed to be updated if the environment was dynamic. Rather than explicitly calculating the free space, it is possible to create a graph which spans through the free space which is computationally efficient.
Gochev et al. [
66] proposed a graph-creating algorithm which used Anytime Repairing A* (ARA*) for state transition graph searching. Here, the idea was based on adaptive dimensionality where a discretized finite state space graph
was built and queried for a path.
had both low-dimensional (3D-TS) regions and high-dimensional (11D-CS) states and transitions.
started as a low-dimensional graph and high-dimensional regions were added iteratively. When adding high-dimensional regions, the low-dimensional states and transitions in the overlapping regions were replaced with their high-dimensional counterparts. State transitions between low-dimensional states and high-dimensional states were replaced as follows. If the state was already in
, then the other state was converted to match the dimension and the edge between those two states was added to
. Then, the graph was searched for a suitable path and if a path was found, all the states and state transitions were converted to high-dimensional components while if a path was not available,
was updated by adding another high-dimensional region. This approach was slower than sampling based planners but bounds on sub-optimality and guarantees on completeness were attractive characteristics.
Kinodynamic Planning by Interior-Exterior Cell Exploration (KPIECE) [
67] iteratively constructed a tree in the state space of the robot. From the initial state, the transitions were calculated using a physics simulation engine (increased accuracy, convenient model construction outweighed the increase in computational cost). The tree expansion was guided by the discretization (a grid) of a projection of the state space. The priority of expansion was given to grid boundaries which were less explored. This algorithm was implemented on a mobile manipulator in [
68].
When motion planning is considered as a trajectory optimization problem, the goal is to find a trajectory that minimizes a given cost function while satisfying the constraints (Note: Even though some of these algorithms were not implemented on a mobile manipulator, those were included for completeness.). Covariant Hamiltonian Optimization for Motion Planning (CHOMP) [
69] used covariant gradient descent (non-stochastic) to minimize a cost function which encoded path smoothness (squared velocity) and obstacle collision (calculated using a precomputed signed distance field) to transform a simple trajectory to a collision-free executable trajectory. The joint limit constraint was satisfied by projecting the joint values to an acceptable range when a violation was detected.
Stochastic trajectory optimization for motion planning (STOMP) [
70] also used optimization to find suitable trajectories. This algorithm used a derivative-free stochastic optimization technique to update a series of noisy initial trajectories. The cost function contained information on obstacles (similar to CHOMP), EE position and/or orientation constraints (cost for violating constraints), and joint torque constraints (Magnitude of torque). The joint limit was considered when generating initial trajectories and due to the convex nature and the smoothing, joint limits were not violated during optimization.
Both CHOMP and STOMP used large number of states to represent a trajectory so that the optimizers were able to safely navigate obstacles while ensuring smoothness.
TrajOpt [
68,
71] tried to account for this problem by considering swept volumes for collision checking which allowed to use sparsely sampled trajectory. The optimization was done with numerical sequential convex optimization with cost being the Euclidean distance in configuration space (encourage minimum-length paths). This algorithm was capable of handling non-holonomic constraints as well.
Gaussian Process Motion Planner (GPMP) [
72] considered the joint space trajectory (position, velocity and acceleration) as a sample from a
vector-valued Gaussian process (GP). This allowed the smooth trajectories to be represented with few states while facilitating the use of Gaussian process regression to calculate robot state for any time of interest. The GP was generated by the linear time varying (LTV) stochastic differential equations (SDEs). The gradient-based optimization was used to minimize the trajectory displacement from the prior mean (keep the trajectory smooth) and obstacle cost (This definition was similar to that of CHOMP [
69] which promoted circumventing obstacles rather than passing them quickly).
Gaussian Process Motion Planner 2 (GPMP2) [
73] solved the trajectory planning problem using probabilistic inference. This formulation required the user to find a
maximum a posteriori (MAP) continuous-time trajectory given the prior distribution (The authors represented the continuous-time joint trajectories as samples from Gaussian Process (GP) [
72]. A Gaussian RBF kernel was used to define prior distribution of trajectories.) and a likelihood function (encoded information about obstacles, start and goal). The MAP estimation problem was then solved using nonlinear least square optimization algorithms (gradient-based) such as Gauss–Newton or Levenberg–Marquardt. This algorithm was implemented on a complete mobile manipulator in [
74].
Simultaneous trajectory estimation and planning (STEAP) [
74,
75] was an improvement from Gaussian Process Motion Planner 2 (GPMP2) [
73] where the likelihood function not only considered collisions, start and goal but also the sensor measurements. The authors specifically defined the configuration space of a mobile manipulator by a Lie group product
where
Lie groups defined the Cartesian coordinates and yaw angle of the mobile base while
n was the DOF of the arm. By incorporating the sensor measurements, better state estimation was achieved which helped to generate better trajectories over GPMP2.
Gupta and Lee [
76,
77] proposed a global path re-planner which used Sequential Quadratic Programming for optimization. Straight line path through way points was planned in the task space and a local planner generated the joint trajectories to follow the EE trajectory. If the joint limits were violated during the trajectory generating process, a small deviation at the point of failure was introduced to the task space trajectory. In calculating this deviation, the authors used Sequential Quadratic Programming to minimize the deviation from the desired trajectory while satisfying joint limits.
Sampling-based planners (RRT [
78], PRM [
79,
80], and EST [
81]) and their variants (RRT-Connect [
68,
82,
83], RRT-GoalBias [
78,
84], Informed RRT, Bidirectional Informed RRT, RRT* [
85], Bidirectional RRT* [
86], Informed RRT* [
87], and Constrained Bidirectional RRT (CBiRRT2) [
88])) have been used for mobile manipulators where the whole system is considered as one high DOF system during the planning process due to planer’s ability to deal with high-dimensional spaces.
In [
89], the RRT algorithm was used with a modification to the local planner where at each iteration, the local planner varied the step length made towards the sample point from the nearest neighbor based on the current lowest path cost and the approximate lowest path cost.
Seyboldt et al. [
90] used the RRT algorithm with the goal specified in the task space. The distance between the task space goal and a node in the tree was calculated by transforming the tree node into the task space using forward kinematics. This distance was used as a heuristic to guide the exploration towards the goal pose. However, as it was not guaranteed to reach the goal pose, tree nodes which were closer to the goal pose were selected, and a direct connection between the tree node and goal pose was attempted using the Jacobian matrix.
A novel sampling-based planning algorithm named XXL was proposed by Luna et al. [
91] where robot’s workspace information was used to guide the planner through the high-dimensional planning space. Even though this method was not tested on a mobile manipulator, the authors state that this algorithm was specially designed to plan the motions of high-dimensional mobile manipulators and related platforms. Here, the robot’s workspace was decomposed, and an informed sampling strategy was developed such that it was possible to generate samples which explicitly projected onto a particular workspace region. However, if the solution was a simple straight-line path, using XXL would be a waste of resources, as XXL had high computational overhead owing to the projection scheme and workspace decomposition.
Several authors have tried to mitigate the inherent issues of sampling based planners using different techniques. In some applications, there were task constraints (e.g., follow a given end effector trajectory) that needed to be satisfied. One approach to address this constraint for sampling based planners was to project (using randomized gradient descent, tangent space sampling or retraction [
92] for articulated manipulators) the random samples onto a sub-manifold which satisfied the task constraint with an acceptable error tolerance.
Another approach was to generate samples by first selecting a task space point from the desired task path and calculating the configuration using inverse kinematics [
93]. This method was further supplemented by using a Jacobian-based equation of motion with motion primitives for motion generation from a selected node which ensured continuous task constraint satisfaction. In [
94], the authors further improved their method by considering dynamic obstacles with known trajectories in the environment. For this, the authors proposed using the RRT algorithm in the task-constrained planning space augmented with the time dimension. Cefalo et al. further improved their method in [
95] where the planner satisfied the task constraint exactly (hard constraint) whenever possible while being capable of exploiting the available constraint tolerances (soft constraints) when needed. In [
95], the authors proposed a heuristic to identify the nodes at which the hard constraint satisfaction was no longer feasible (number of vertices on the frontier leaf (indicate that frontier leaf has been sufficiently explored) and number of failed expansions (indicate that sufficient number of extensions have been attempted, i.e., kinematic redundancy has been fully exploited)) and becomes feasible again (number of collision free configurations out of randomly generated configurations on the next leaf). However, these methods only considered the end effector position as a task constraint not the orientation.
Zhu et al. [
96] proposed a method to generate paths online for a mobile manipulator. A large database of paths was generated offline (using CBiRRT2 [
88]) (Database included start and goal configurations, generated paths, swept volume of the robot, and environments.) and during the online path generation phase, the start configuration and the goal configuration were extracted from the database based on a nearest neighbor search. Then, for those start and goal configurations, a path (or a combination of paths) was selected from the database using A* algorithm. The path from the approximate goal to the actual goal was separately planned (can be done in parallel once the approximate goal was decided to speed up the algorithm). For fast collision checking, swept volume of the robot along the planned path was used. Even though this method allowed for online path generation, significant offline date generation was needed to build a sufficient database while the generated path quality directly depended on the quality of the database.
Task Space RRT (TS-RRT) [
97] was introduced by Shkolnik and Tedrake where the nodes contained both the task space information and configuration while the sample generation, nearest neighbor search and path extend were done in the task space. Heuristic map-guided TS-RRT (HM-TS-RRT) [
98] was an improvement of TS-RRT where a heuristic map of the task space was used to guide the exploration (The nearest neighbor was selected from a set of nodes whose heuristic value is low.) instead of just pure exploration. The heuristic map represented the distance to the goal and distance from obstacles. The map was calculated using a 3D-CNN architecture named Heuristic Map Networks (HMNet).
In [
99], the authors used a modified version of RRT-Connect to plan mobile manipulator motions. Along with the conventional approach to connecting the two trees, the authors proposed to extend the two trees along a linking line between the two trees. This greatly reduced the number of nodes.
Yang et al. [
100] proposed a modified RRT-Connect planner which plans in the configuration space augmented by time. This was a geometric planner whereby adding the time dimension, the joint velocity was considered implicitly during the planning stage. The planner was capable of generating motion plans for moving object grasping but the object trajectory needed to be known in advance. The time dimension of a generated sample was modified if there was no valid nearest neighbor that could be reached while satisfying joint velocity limits.
These sampling-based planners are capable of finding solutions but the path quality in terms of smoothness can be low resulting in jerky motion of the system. To deal with this issue, various smoothing techniques have been proposed but this is less effective in cluttered environments. Shao et al. [
84] proposed a postprocessing technique for a path generated by RRT-GoalBias [
78] where motion between two non-adjacent nodes was replaced with a linear motion discarding the intermediate nodes provided that the linear motion was collision free. Further, sampling-based algorithms are only probabilistic complete and may provide different solutions during different runs due to random nature.
While the above algorithms were capable of generating a path, they did not consider the dynamic limitations of the system. Both works in [
101,
102] considered the system dynamics in order the limit the actuator torques.
Haddad et al. [
101] adapted the Random Profile Approach (RPA) [
103] which was proposed for fixed base manipulators to mobile manipulators. This method was capable of handling dynamic constrains (active joint torque bounds) along with collisions and other physical constraints. This trajectory optimization method calculated time-scaled trajectory profiles where the trajectory time was bounded by the kinodynamic constraints. To do this, the problem was reduced to a single parameter profile optimization problem and solved using simulated annealing method. This method required an initial trajectory to be planned using another method, and the optimized trajectory belonged to that homotopy class.
Continuous Clonal Selection Algorithm based on wavelet mutation (CCSA-WM) was used to minimize the joint torques in [
102]. The joint torques were represented using a 5th order polynomial which were mutated using a Artificial Immune System (AIS) Algorithm. At each iteration, the system’s state was calculated by applying the joint torques on the system’s dynamics equation. If the desired goal state was not reached, the authors suggested to divide the final time segment into two (break point decided by AIS) and calculated a separate polynomial from the break point to reach the exact goal state (This was possible as the break point state values were not fixed.).
In [
104], the trajectories were sampled from a Gaussian process (GP) but the optimization cost only encoded information about collision avoidance. Authors stated that it was possible to consider additional cost items such as task constraints, joint torques, and manipulability. The cost was optimized using a derivative-free cross-entropy stochastic optimization algorithm which was less prone to local minima than gradient based algorithms. This method allowed the algorithm to store a smaller number of states while facilitating parallel processing for speed.
Evolutionary strategy rather than Genetic Algorithm was used in [
105] to plan a EE trajectory. The trajectory was modeled as a B-spline, and the data points for the B-pline were calculated using Evolutionary strategy which considered motion smoothness (squared integration of time derivative for each joint torque), joint limits, manipulator singularity, and stability (zero-Moment Point (ZMP) [
106]). This was implemented on a non-redundant mobile manipulator, but the authors suggested that it can be extended to redundant manipulators easily.
Abdessemed [
107] formulated the forward kinematics equation of a mobile manipulator as a pseudo neural network and used that to calculate the configurations for a given EE trajectory. At each time, the previous time stamp’s configuration was used as input to the network to calculate the EE position. Then, EE error (Euclidean distance by comparing with the required EE position) was calculated and back propagation was done to update the weights (using Levenberg–Marquardt algorithm). Then, the input vector was multiplied with the updated weight vector to get the next time stamp’s configuration. This algorithm was applied on a redundant robot but only EE position was considered.
Sequential Expanded Lagrangian Homotopy (SELH) approach proposed in [
108] sequentially calculated the configurations for a given EE path. The algorithm calculated the configuration for each point in the discretized trajectory by optimizing manipulability index [
42] using SELH where the algorithm used the knowledge from the previously calculated configuration in the next configuration calculation. This method was able to easily integrate collision avoidance, soft task constraints, and dynamic obstacles (as the problem is solved sequentially); however, the final solution quality significantly depended on the start configuration (Calculated offline to get several good guesses).
In [
109], performance of different metaheuristic algorithms was compared when generating the configurations for a given EE trajectory. The authors used a cost function which accounted for the EE error, distance from the previous configuration, and a penalty term for violating joint limits. Different algorithms (CS—Cuckoo Search, DE—Differential Evolution, HBBO—Human behavior-based optimization, PSO—Particle Swarm Optimization, and TLBO—Teaching-Learning-Based Optimization) were implemented and simulated. The authors concluded that DE algorithm outperforms others with respect to the cost and computational time.
Costanzo et al. [
110] used a mobile manipulator for the task of shelf replenishment. A new grasp pivoting method was introduced which allowed the gripper to change the grasp configuration without re-grasping the object. This effectively added another constrained DOF to the robot and required a planner capable of efficiently handling constraints. Authors used the learned action generation models proposed in [
111] to plan for the 10-DOF system (Mobile base—3, Manipulator—6, Gripper virtual joint—1).
Reinforcement Learning (RL) techniques was used in [
112] for mobile manipulator pick-up tasks. The planning was carried out in the state space which encoded the position of the gripper w.r.t the robot base frame, the position of object w.r.t the gripper frame, the position of object w.r.t the robot base frame, the joint positions and velocities of the arm, as well as the gripper state. The RL module was trained using Proximal Policy Optimization (PPO) algorithm. The RL model was able to calculate the EE position actions, mobile base pose actions, and gripper action which were required to pick-up an object from a random pose.
Summary of motion planning algorithms discussed in this section is included in
Table 2 (properties of these planners are summarized in
Appendix B.1). Motion planning in the high-dimensional space is not only computationally expensive, but also the generated paths can be of low quality. Due to the randomness of the sampling based planners, there may be unnecessary motions of the manipulator even after post smoothing processes. In most cases, it is sufficient to move the mobile base only, the manipulator motion is required only at certain base poses. These issues can be solved by coordinating the two subsystems.
3.2.2. Two Subsystems—Different Capabilities
The information about the different characteristics of the two subsystems can be used for making planning decisions.
Perrier et al. [
114,
115] proposed to use dual quaternions to represent a robot’s state where the non-holonomic motion of the mobile base was represented as a constrained displacement in the quaternion space. The motion planning problem was reduced to just iteratively moving the mobile manipulator towards the goal in planar quaternion space. Even though this approach was associated with simple matrix arithmetic, the planned path needed to be transformed from the quaternion space to configuration space. One of the main advantages of using dual quaternions was the insensitivity to measurement units as opposed to using homogeneous matrices.
A motion graph was built in [
116] by sequentially applying motion primitives on the system (similar to the work in [
117]). From the start configuration, forward motion of the mobile manipulator was obtained by applying several control inputs to the system. Then, a node was selected based on a metric and motion primitives were applied again. The number of acceptable control inputs was termed as Feasible Acceleration Count (FAC) where those control inputs were calculated such that the mobile base was always in contact with the ground and the friction cone constraint was satisfied for the wheel–ground contact (tip-over stability). The next node to be extended was selected based on the FAC and the geodesic distance to the goal. This algorithm was applied on a system navigating on an uneven terrain which showed the planner’s ability to keep the mobile manipulator stable without tipping over.
In [
118], the authors used the FAC in conjunction with a RRT-like algorithm. The control inputs available for the local planner to extend from a particular node were selected for the collection of Feasible Accelerations. In selecting a node to be extended from, rather than using the closest node to the random configuration, a node with the highest ratio of FAC to geodesic distance to the goal was selected. Because of this, stability and maneuverability of the robot was promoted in an uneven terrain.
Lamiraux et al. [
119] proposed an extension of RRT algorithm to be used for mobile manipulation where the planning problem was represented through a constraint graph. This allowed the planning algorithm to handle implicit and explicit constraints. In [
120], the authors extended their work by decomposing the planned path into different segments based on the constraint graph and generating a suitable controller for each segment based on the planned path and available visual information.
Oriolo and Mongillo [
121] proposed a variant of RRT for following a given EE path. The main contribution was related to the sample generation algorithm specifically dealing with kinematic redundancies. The configuration space was divided into two partitions:
base variables and
redundant variables. The authors selected the configuration variables of the mobile base as redundant variables. For each point in the trajectory, redundant variables were sampled randomly and then the configuration of the manipulator was calculated using inverse kinematics. If the inverse kinematic solution was available, the combined configuration was used by the planner. The redundant variables were sampled from a coarse estimation (circle with radius equal to sum of link lengths) of the mobile base locations such that the end effector pose was reachable. If a biasing configuration parameter (e.g., the goal configuration) was given to the sample generation algorithm, the redundant variables were generated by first selecting a pseudovelocity which optimized some criteria (weighted Euclidean distance between configurations or Task compatibility of the manipulator) and then moving the system according to the selected pseudovelocity by using the system’s equation of motion.
Hierarchical and adaptive mobile manipulator planner (HAMP) [
122] proposed by Pilania and Gupta was another method that planned with adaptive dimensionality. HAMP first planed the mobile base path using PRM considering a fixed manipulator configuration. Then, for each edge along the path (found using a variant of Dijkstra’s algorithm with Euclidean distance as the cost), collision between the manipulator and the environment was checked and if there was collision, the manipulator was moved to a new configuration by building a manipulator PRM such that collision was avoided along the mobile base edge. In [
123], the authors further improved the algorithm to HAMP-U which considered the mobile base pose uncertainty during the planning process.
Optimized Hierarchical Mobile Manipulator Planner (OHMP) [
124] was proposed by Li et al. to deal with the narrow passage exploration problem in PRM by using a hybrid sampling strategy (Hybrid Randomized Bridge Builder (HRBB) [
125]. The authors defined a narrow passage as a space where the width was less than the diameter of the manipulator’s reachable workspace. First, a path was planned for the mobile base using PRM and at each mobile base node, if the manipulator was in collision, the manipulator was moved to a safe configuration. This was another planner with adaptive planning dimension where the planning dimension was increased only when required. However, various parameters were required to be tuned in order to achieve superior performance while collision checking for the manipulator was carried out using a 2D projection onto the floor. To get smooth trajectories for the manipulator, the authors used cubic polynomials.
Bidirectional Informed RRT* (BI2RRT*) was proposed in [
113] (Extension of Informed RRT* [
87]) which quickly generated an initial path and improved the path if more planning time was available. Once an initial path was found, informed sampling was carried out from two hyperellipsoids (One for revolute components of the mobile manipulator and one for prismatic components) which were centered around current nodes. To satisfy task constraints, a first-order retraction method [
92] was used for sample projections.
In [
126,
127], the authors used CBiRRT2 [
88] for motion planning. The tasks were categorized into two types: move the EE accurately to the goal, and exert a large force by EE. To move accurately to a goal pose, the manipulator motion needed to be given prominence and it was easier to exert forces using the mobile base. These two types of motions were prioritized by using proper weighing matrix in calculating the distance between two configurations.
Kang et al. [
128] proposed a new sampling approach for LazyPRM* [
129] to be used for motion planning of mobile manipulators. Their sampling method named
Harmonious sampling was used for optimal motion planning which helped to efficiently explore the high-dimensional configuration space of both the mobile base and the robot manipulator. This sampling method adjusted the planning space dimension in such a way that in complex regions both the base and the manipulator were moved simultaneously while in other regions only the mobile base was moved. The authors defined two complex regions: near the end effector goal pose and near obstacles creating narrow passages. This was also another planner with adaptive dimensionality.
Time-optimal local planners for a differentially driven robot were introduced in [
130]. In [
131], the authors further introduced two concepts named
detachability and
time dominance which expanded the suggested local planners when planning for mobile manipulators. Detachability was related to the cost function where if satisfied, it allowed to join new local planners to the previously available ones. When planning for a mobile manipulators, this property allowed the use of local planners developed for mobile bases coupled with local planners for manipulators rather than developing new local planners for the whole system from scratch. The algorithms were tested on a mobile manipulator performing a task of moving between two configurations while maintaining an object within manipulator-mounted camera’s FoV.
Hybrid Sampling-based Bi-directional RRT (HS-Bi-RRT) [
132] used a hybrid sampling strategy with BiRRT in configuration space for path planning (Alternate Task space and Configuration Space Exploration (ATACE)). The free space (the authors named this as
focus region) for the mobile base was represented as a collection of overlapping disks and for the manipulator’s end effector, free space was represented using overlapping spheres. The trees were grown in the configuration space, but each node included information about the EE pose as well. The hybrid sampling was done on the configuration space (mobile base position inside a disk while mobile base orientation and manipulator configuration were random) or on the task space (Homogeneous matrix such the EE position was within a focus sphere). As the mobile base was non-holonomic, in finding the nearest neighbor, first, few neighbors were found considering only the mobile base position and then one was selected based on the closeness in manipulator’s configuration space.
RRT*-Constrained Riemannian Mapping Manipulability (RRT*-CRMM) was introduced in [
133]. The samples were obtained from the point cloud which represented the object to be manipulated and the configuration was obtained using constrained Jacobian matrix. The cost between two configurations accounted for EE displacement, manipulability, and movement of the mobile base.
Lee et al. [
134] used the Genetic algorithm in calculating commutation configurations (Intermediate configurations for several sequential EE poses) while the cost to be optimized was a weighted average between the cost of the current EE pose (Encode information about obstacle avoidance, joint limits, joint torque limits) and the cost of the path to the next EE. Once the commutation configurations were decided, the trajectory between two configurations was planned using Lagrangian formulation while the path cost included costs related to obstacle avoidance, joint torques and manipulability.
In [
135], the authors addressed the problem of mobile base placement for several sequential EE poses. The optimum configurations for each EE pose were calculated using the Genetic Algorithm which minimized the number of mobile base movements and change in manipulator configuration subject to joint angle limits and collision avoidance. The path between these optimum configurations was planned using RRT-Connect algorithm.
Mobile manipulator path for a given EE trajectory was calculated using Full Space Parameterization (FSP) with Lagrangian optimization [
136]. The inverse kinematics problem for each EE pose was solved using Lagrangian optimization where the non-holonomic constraint was linearized about the current operating point and was included in the optimization process.
The Augmented Lagrangian Method was used for optimization in [
137] to calculate the mobile manipulator configurations for a given EE trajectory. The cost to be minimized was the Euclidean distance in configuration space (Mobile base movements were penalized more) while reaching the desired EE position and maintaining a desired manipulability. Furthermore, the authors suggested to have a upper bound on yaw angle of the mobile base to ensure acceptable path curvature.
Real-Time Adaptive Motion Planning (RAMP) [
138] was similar to the Evolutionary algorithms in path planning with few with differences (used random selections and random modification operations, drastic changes rather than small changes (mutations), and less tuning parameters (just population size)). The planner modified the paths to account for the motion of the obstacles at each planning cycle. The path feasibility was checked considering execution time, energy consumption and manipulability index. Manipulator trajectory was represented using cubic splines while the mobile base trajectory was a linear trajectory with parabolic bends where both trajectories were loosely coupled by having few connected configurations (Knot points).
In [
139], the authors collected path data from a demonstration by a human. Then, during the path planning process, each configuration in the path was modified to account for the mobile base pose error and the distance to obstacles to get a better path. The authors used their previous knowledge [
140] to quantify the effect of base pose error on the EE pose error.
Welschehold et al. [
141] also learned the motions by human demonstration. The task of moving through a doorway was executed using the paths generated by the learned model. The demonstrations were linked to the robot motions by formulating a graph and carrying out optimization to satisfy the robot’s kinematic constraints. One of the main benefit in this approach was that the demonstrations did not needed to be tailored to robot learning.
In [
142], the authors proposed HRL4IN, a novel hierarchical RL architecture for interactive navigation tasks. The RL model was trained to efficiently use mobile base navigation, manipulator motion, and their combination in different phases of the task. The model was able to generate velocity commands to drive the robot towards the goal.
Raja et al. [
143] used modified Kohonen Self-Organizing Map (KSOM) to calculate the mobile manipulator configurations for a given EE trajectory. A mapping between the task space and configuration space was learned while maximizing manipulability and minimizing the end effector error. More weightage was given to the mobile base movement in the cost function to restrict the heavier mobile base movement.
In [
144], Zhang et al. proposed to use the
Capability map and the
Inverse Capability map for motion planning. The motion planning task was to define a path for a given end-effector trajectory such the manipulator maintains high manipulability by coordinating between the mobile base and the manipulator. First, for each of the discretized points in the end effector trajectory, a set of suitable mobile base configurations were calculated using the capability map of the manipulator. Then, an initial path for the mobile base through these point sets were calculated by starting from the initial pose and iteratively selecting the nearest pose from the next pose set. This initial path was then optimized to yield the shortest path by using hyper-ellipsoids where configurations were sampled from the hyperellipsoid and if the path through the new configuration was shorter, the path was updated. Once the base poses were finalized, the manipulator configurations were calculated using inverse kinematics. One of the main contributions in this work was on fast algorithm for generating a set of suitable mobile base poses for a given end effector pose. As the mobile base needed to be upright i.e., roll and pitch angles needed to be zero, the capability map was filtered to remove points that violated those conditions which significantly reduced the number of points in the capability map. Then, the feasible mobile base configurations were calculated and further filtered to remove points with low manipulability.
Welschehold et al. [
145] used the obstacle avoidance principle introduced by [
146] to calculate the mobile base poses such that the given EE poses were reachable. The suitable base pose bounds were modeled as ellipses where the inner bound was treated as an obstacle (to keep the mobile base away from that region) while the outer bound was treated as an inverse obstacle to keep the mobile base within the outer bounds. However, only the mobile base position was handled by the above method where the acceptable orientation ranges were obtained from a lookup table based on the EE pose and mobile base pose.
Summary of motion planning algorithms discussed in this section is included in
Table 3 (properties of these planners are summarized in
Appendix B.2).