Computing bounds on joint angles

The main requirement for successful application of the method is the ability to compute bounds on how far a chain of links can travel in $ {\cal W}$ over some range of joint variables. For example, for a planar chain that has revolute joints with no limits, the chain can sweep out a circle as shown in Figure 7.26a. Suppose it is known that the angle between links must remain between $ -\pi/6$ and $ \pi/6$. A tighter bounding region can be obtained, as shown in Figure 7.26b. Three-dimensional versions of these bounds, along with many necessary details, are included in [244]. These bounds are then used to compute $ I_i$ in each iteration of the sampling algorithm.

Now that there is an efficient method that generates samples directly in $ {{\cal C}_{clo}}$, it is straightforward to adapt any of the sampling-based planning methods of Chapter 5. In [244] many impressive results are obtained for challenging problems that have the dimension of $ {\cal C}$ up to $ 97$ and the dimension of $ {{\cal C}_{clo}}$ up to $ 25$; see Figure 7.27. These methods are based on applying the new sampling techniques to the RDTs of Section 5.5 and the visibility sampling-based roadmap of Section 5.6.2. For these algorithms, the local planning method is applied to the active variables, and inverse kinematics algorithms are used for the passive variables in the path validation step. This means that inverse kinematics and collision checking are performed together, instead of only collision checking, as described in Section 5.3.4.

One important issue that has been neglected in this section is the existence of kinematic singularities, which cause the dimension of $ {{\cal C}_{clo}}$ to drop in the vicinity of certain points. The methods presented here have assumed that solving the motion planning problem does not require passing through a singularity. This assumption is reasonable for robot systems that have many extra degrees of freedom, but it is important to understand that completeness is lost in general because the sampling-based methods do not explicitly handle these degeneracies. In a sense, they occur below the level of sampling resolution. For more information on kinematic singularities and related issues, see [693].

Figure 7.27: Planning for the Logabex LX4 robot [187]. This solution was computed in less than a minute by applying active-passive decomposition to an RDT-based planner [244]. In this example, the dimension of $ {\cal C}$ is $ 97$ and the dimension of $ {{\cal C}_{clo}}$ is $ 25$.
\begin{figure}\centerline{\psfig{figure=figs/logabex.ps,width=\columnwidth} }\end{figure}

Steven M LaValle 2020-08-14