In recent years, the application of UAV drones in various fields such as intelligent inspection, emergency rescue, and security monitoring has expanded significantly. However, autonomous flight in complex indoor environments presents unique challenges that have become a focal point of research. Compared to outdoor settings, indoor spaces are typically characterized by enclosed structures, dense obstacles, unavailable GPS signals, small spatial scales, and variable layouts. These factors impose higher demands on trajectory planning in terms of precision, safety, and real-time performance. In this context, developing efficient and feasible trajectory planning methods for indoor environments holds substantial theoretical value and practical significance. The core challenges for indoor UAV drones include spatial constraints and obstacle complexity, dynamic feasibility requirements for trajectories, and real-time adaptability issues. UAV drones must navigate narrow corridors, corners, or areas with varying heights while avoiding obstacles flexibly. Traditional global planning methods often struggle with non-convex obstacle spaces. Moreover, trajectories for UAV drones must simultaneously satisfy smoothness, dynamic constraints, and collision safety. Planning algorithms need to output not only collision-free paths but also ensure controllability and executability. Additionally, in scenarios involving environmental changes, dynamic obstacles, or partial sensor failures, planning systems require rapid response capabilities and autonomous adjustment abilities.

Current research on trajectory planning for UAV drones has proposed various methods. Typical approaches are based on grid search, such as the A* algorithm, or sampling-based techniques like the Rapidly-exploring Random Tree (RRT) and Probabilistic Roadmap (PRM). These are often combined with optimizers like Minimum Snap, TrajOpt, or CFS to form a two-stage framework of “front-end path generation + back-end trajectory optimization.” Furthermore, some studies utilize reinforcement learning or topological priors to enhance search efficiency and trajectory quality. However, these methods still have limitations in complex indoor environments: limited adaptability to non-convex spaces, unreasonable time allocation strategies, and inaccurate modeling of kinematic and dynamic constraints, resulting in trajectories that struggle to balance smoothness, feasibility, and robustness. Recently, Batch Informed Trees (BIT*) has been widely applied to path planning in complex environments due to its asymptotic optimality and efficient sampling utilization. Compared to traditional sampling methods, BIT* offers advantages in search efficiency and global quality. However, existing BIT* implementations often remain at the geometric feasibility level, lacking constraints on the dynamic characteristics of UAV drones. The generated paths may be optimal in geometry but could be infeasible in practice due to violations of velocity, acceleration, or thrust limits, thereby increasing the burden on back-end trajectory optimization.
To address these issues, we propose an improved dynamically feasible BIT* method and integrate it with a trajectory optimizer to construct a unified “search-constraint-optimization” framework. In the search phase, dynamic constraints are introduced as filters, ensuring that candidate paths are feasible and reasonable from the outset, thus reducing subsequent optimization difficulty. In the optimization phase, smoothing techniques are applied to further enhance trajectory quality. This paper validates the proposed method through simulations, systematically evaluating its comprehensive performance in obstacle avoidance and trajectory smoothness, providing support for engineering applications of indoor intelligent flight systems for UAV drones.
For indoor inspection UAV drones, we first establish a comprehensive mathematical model. The overall structure of the UAV drone is considered, with a body-fixed coordinate system denoted as {B} and an Earth-fixed coordinate system denoted as {E}. We assume the UAV drone is a rigid body, and gravity remains constant during flight. The dynamics modeling involves both translational and rotational motions. Based on Newton-Euler equations, the system dynamics model can be expressed as:
$$ \begin{bmatrix} m \dot{V}^E \\ J^B \dot{\Omega}^B \end{bmatrix} + \begin{bmatrix} 0 \\ \Omega^B \times J^B \Omega^B \end{bmatrix} = \begin{bmatrix} F^E \\ M^B \end{bmatrix} $$
Here, $V^E = [u, v, w]^T$ represents the linear velocity in the Earth frame, $\Omega^B = [p, q, r]^T$ represents the angular velocity in the body frame, $J^B = [J_x, J_y, J_z]^T$ is the moment of inertia, $F^E$ is the total external force in the Earth frame, and $M^B$ is the total external moment in the body frame. The total external force $F^E$ consists of lift force $F^E_T$, gravity $F^E_G$, aerodynamic drag $F^E_D$, and unmodeled forces $\Delta F^E$:
$$ F^E = F^E_T + F^E_G + F^E_D + \Delta F^E $$
Where $F^E_G = [0, 0, mg]^T$, with $m$ as mass and $g$ as gravitational acceleration. The lift force $F^E_T$ is given by:
$$ F^E_T = -R^E_B C_T \sum_{i=1}^{4} \omega_i^2 $$
$R^E_B$ is the rotation matrix from body to Earth frame, $C_T$ is the thrust coefficient, and $\omega_i$ is the rotational speed of the $i$-th rotor. The total external moment $M^B$ includes moments from thrust $M^B_T$, gyroscopic effects $M^B_a$, drag torque $M^B_D$, and unmodeled moments $\Delta M^B$:
$$ M^B = M^B_T + M^B_a + M^B_D + \Delta M^B $$
The thrust moment $M^B_T$ is:
$$ M^B_T = \begin{bmatrix} \sin(\pi/4) C_T L (-\omega_1^2 + \omega_2^2 + \omega_3^2 – \omega_4^2) \\ \cos(\pi/4) C_T L (\omega_1^2 + \omega_2^2 – \omega_3^2 – \omega_4^2) \\ 0 \end{bmatrix} $$
Where $L$ is the distance from each rotor center to the system’s center of mass. The gyroscopic moment $M^B_a$ is:
$$ M^B_a = \sum_{i=1}^{4} \left( J_{\text{gyro}} \left( \Omega^B \times \begin{bmatrix} 0 \\ 0 \\ 1 \end{bmatrix} \right) (-1)^{i+1} \omega_i \right) $$
$J_{\text{gyro}}$ is the total moment of inertia of the motor and rotor about the rotation axis. The drag torque $M^B_D$ is:
$$ M^B_D = \begin{bmatrix} 0 & 0 & \sum_{i=1}^{4} (C_D (-1)^{i+1} \omega_i^2) \end{bmatrix}^T $$
$C_D$ is the drag torque coefficient. Thus, the detailed dynamics model for UAV drones is:
$$ \begin{bmatrix} m \dot{V}^E \\ J^B \dot{\Omega}^B + \Omega^B \times J^B \Omega^B \end{bmatrix} = \begin{bmatrix} F^E_T + F^E_G + F^E_D + \Delta F^E \\ M^B_T + M^B_a + M^B_D + \Delta M^B \end{bmatrix} $$
The kinematics model describes the relationship between position and velocity, as well as attitude angles and angular rates. The system kinematics equations are:
$$ \begin{cases} \dot{P}^E = V^E \\ \dot{\Theta} = W^B \Omega^B \end{cases} $$
Where $P^E = [x, y, z]^T$ is the position in the Earth frame, $\Theta = [\phi, \theta, \psi]^T$ are the Euler angles (roll, pitch, yaw), and $W^B$ is the transformation matrix:
$$ W^B = \begin{bmatrix} 1 & \tan(\theta) \sin(\phi) & \tan(\theta) \cos(\phi) \\ 0 & \cos(\phi) & -\sin(\phi) \\ 0 & \sin(\phi)/\cos(\theta) & \cos(\phi)/\cos(\theta) \end{bmatrix} $$
An important property for trajectory planning of UAV drones is differential flatness. For quadrotor UAV drones, the system is differentially flat with flat outputs being the position coordinates and the yaw angle. This means all state variables and control inputs can be expressed as algebraic functions of these flat outputs and their derivatives. Specifically, for flat outputs $\sigma = [x, y, z, \psi]^T$, the attitude angles $\phi$ and $\theta$ can be derived from the desired acceleration and yaw angle. This allows us to focus on planning trajectories in the position space while ensuring dynamic feasibility. The body frame Z-axis direction is given by:
$$ Z_B = \frac{F^E_T}{\|F^E_T\|} $$
And the intermediate frame C is introduced, which is aligned with the Earth frame but rotated by the yaw angle $\psi$. From this, the rotation matrix $R^E_B$ can be computed, and the angular velocities $p, q, r$ can be solved as functions of the flat outputs and their derivatives. This property simplifies trajectory planning for UAV drones, as we only need to parameterize position and yaw, avoiding direct modeling of the highly nonlinear attitude space.
Building on this mathematical foundation, we propose an improved dynamically feasible algorithm based on BIT* for trajectory planning of UAV drones. Traditional sampling-based planners like BIT* generate geometrically feasible paths but often produce polyline segments that are not smooth and may violate dynamic constraints. Our approach, termed Dynamics Feasibility Batch Informed Trees (DF-BIT*), embeds dynamic constraints during the search phase to ensure that candidate trajectories are executable by UAV drones. The standard BIT* algorithm involves initialization, batch sampling, vertex expansion, edge processing, and pruning. In DF-BIT*, we modify key steps to incorporate dynamic feasibility checks. During vertex expansion, when constructing candidate edges, we use a dynamic constraint filter to evaluate whether the edge satisfies velocity and acceleration limits. For UAV drones, we set maximum velocity $v_{\text{max}} = 5 \, \text{m/s}$ and maximum acceleration $a_{\text{max}} = 3.5 \, \text{m/s}^2$ for indoor environments, considering factors like obstacle density, narrow passages, and control uncertainties. The feasibility condition for an edge from vertex $v$ to $x$ is:
$$ \text{Feasibility}(v, x) = \begin{cases} 1 & \text{if } \| \dot{x} \| \leq v_{\text{max}} \text{ and } \| \ddot{x} \| \leq a_{\text{max}} \text{ for all discrete points} \\ 0 & \text{otherwise} \end{cases} $$
Only feasible edges are added to the priority queue for further processing. This prevents the generation of infeasible trajectory segments and improves search efficiency. Additionally, during pruning, we use dynamic reachability heuristics to eliminate samples and vertices that are unlikely to yield feasible paths, reducing computational redundancy. The DF-BIT* algorithm flow includes steps like parameter initialization, batch sampling, candidate vertex and edge set construction, vertex expansion with dynamic feasibility checks, edge evaluation and update, and termination condition checking. By integrating dynamic constraints early in the search, DF-BIT* ensures that the resulting paths are not only collision-free but also dynamically executable for UAV drones.
However, the paths generated by DF-BIT* may still consist of discrete waypoints connected by straight lines, which are not smooth enough for UAV drones to track precisely. Therefore, we apply a trajectory optimization method based on B-spline curves to transform the discrete path into a smooth trajectory that satisfies higher-order continuity constraints. B-spline curves offer advantages such as adjustable continuity and local control, making them suitable for optimizing paths for UAV drones. A B-spline curve of degree $p$ is defined as:
$$ C(t) = \sum_{i=0}^{n} P_i N_{i,p}(t), \quad t \in [t_p, t_{m-p}] $$
Where $P_i$ are control points, $N_{i,p}(t)$ are basis functions defined by the Cox-de Boor recursion formula:
$$ N_{i,0}(t) = \begin{cases} 1 & \text{if } t_i \leq t < t_{i+1} \\ 0 & \text{otherwise} \end{cases} $$
$$ N_{i,p}(t) = \frac{t – t_i}{t_{i+p} – t_i} N_{i,p-1}(t) + \frac{t_{i+p+1} – t}{t_{i+p+1} – t_{i+1}} N_{i+1,p-1}(t) $$
The knot vector is $t = (t_0, \ldots, t_m)$ with $m = n + p + 1$. We use cubic B-splines ($p=3$) for trajectory optimization. The optimization objective is to minimize the squared derivatives of the curve to ensure smoothness, which is crucial for the stable flight of UAV drones. The cost function is:
$$ J(P) = \int_{t_a}^{t_b} \| C^{(k)}(t) \|^2 dt = \int_{t_a}^{t_b} \left\| \sum_{i=0}^{n} P_i N_{i,p}^{(k)}(t) \right\|^2 dt $$
Where $C^{(k)}(t)$ is the $k$-th derivative of the curve. This can be expressed in matrix form as $J(P) = P^T Q P$, where $Q_{ij} = \int_{t_a}^{t_b} N_{i,p}^{(k)}(t) N_{j,p}^{(k)}(t) dt$. Constraints include boundary conditions for position, velocity, and acceleration at the start and end points, as well as dynamic constraints during flight:
$$ \| \dot{C}(t) \| \leq v_{\text{max}}, \quad \| \ddot{C}(t) \| \leq a_{\text{max}} $$
These constraints ensure that the optimized trajectory remains feasible for UAV drones. The problem becomes a quadratic programming (QP) problem:
$$ \min_{P} \frac{1}{2} P^T Q P \quad \text{subject to} \quad A_1 P = b_1, \quad A_2 P \leq b_2 $$
Which can be solved using standard QP solvers. By applying this optimization to the path from DF-BIT*, we obtain a smooth trajectory that satisfies both geometric and dynamic constraints for UAV drones.
To validate our proposed method, we conduct simulation experiments in MATLAB and ROS environments. The parameters for the UAV drone are summarized in the following table:
| Parameter | Symbol/Unit | Value |
|---|---|---|
| Mass | $m$ (kg) | 0.75 |
| Gravity acceleration | $g$ (m/s²) | 9.81 |
| Moment of inertia (x-axis) | $J_x$ (kg·m²) | 0.015 |
| Moment of inertia (y-axis) | $J_y$ (kg·m²) | 0.015 |
| Moment of inertia (z-axis) | $J_z$ (kg·m²) | 0.024 |
| Thrust coefficient | $C_T$ | 3.3 × 10⁻⁵ |
| Drag torque coefficient | $C_D$ | 5.5 × 10⁻⁷ |
| Rotor radius | $r$ (cm) | 4.5 |
| Arm length | $2L$ (mm) | 152 |
| Frontal area | $A$ (m²) | 4.3 × 10⁻³ |
| Number of samples | N/A | 100 |
| Maximum velocity | $v_{\text{max}}$ (m/s) | 5 |
| Maximum acceleration | $a_{\text{max}}$ (m/s²) | 3.5 |
| Maximum edge length | $r_{\text{bit}}$ (cm) | 50 |
We compare the performance of DF-BIT* with traditional RRT* and BIT* algorithms. The simulation results show that DF-BIT* generates trajectories with fewer polyline segments and better adherence to dynamic constraints. The following table summarizes the violations of dynamic limits for each algorithm:
| Algorithm | Number of Violations | Maximum Velocity (m/s) | Maximum Acceleration (m/s²) |
|---|---|---|---|
| RRT* | 7 | 10.0 | 15 |
| BIT* | 4 | 6.5 | 8 |
| DF-BIT* | 0 | 4.0 | 3 |
As seen, DF-BIT* produces trajectories that strictly satisfy the dynamic constraints, making them more suitable for UAV drones. Additionally, we evaluate algorithm performance in terms of iteration count, computation time, and path length:
| Algorithm | Iterations | Computation Time (s) | Path Length (m) |
|---|---|---|---|
| RRT* | 3000 | 4.5 | 30.0 |
| BIT* | 2800 | 3.2 | 25.8 |
| DF-BIT* | 2000 | 2.5 | 24.1 |
DF-BIT* achieves fewer iterations, shorter computation time, and shorter path length, demonstrating its efficiency and effectiveness for UAV drones in indoor environments. After obtaining the path from DF-BIT*, we apply B-spline optimization to generate a smooth trajectory. The optimization results show that the discrete waypoints are transformed into a continuous curve with smooth velocity and acceleration profiles. The velocity and acceleration curves are constrained within the limits, ensuring dynamic feasibility for UAV drones. The optimized trajectory is collision-free and satisfies all constraints, providing a reliable solution for autonomous flight of UAV drones in narrow indoor spaces.
In conclusion, this paper addresses the trajectory planning problem for indoor inspection UAV drones by developing a comprehensive framework that integrates dynamic constraints and smooth optimization. We propose an improved DF-BIT* algorithm that embeds dynamic feasibility checks during the search phase, ensuring that generated paths are executable by UAV drones. Furthermore, we employ B-spline-based trajectory optimization to enhance smoothness and controllability. Simulation results validate that our method produces feasible and smooth trajectories, outperforming traditional algorithms in terms of dynamic compliance and efficiency. This work contributes to the advancement of autonomous flight capabilities for UAV drones in complex indoor environments. Future research will focus on real-time perception in unknown environments and rolling horizon planning mechanisms to enable UAV drones with autonomous exploration and dynamic obstacle avoidance abilities. The integration of advanced sensors and adaptive control strategies will further enhance the robustness and applicability of UAV drones in real-world indoor scenarios.
The mathematical modeling, algorithm design, and optimization techniques presented here provide a solid foundation for deploying UAV drones in various indoor applications, such as infrastructure inspection, search and rescue, and surveillance. By ensuring dynamic feasibility and smooth trajectories, we mitigate risks associated with unstable flight and collisions, making UAV drones more reliable and efficient tools. The continuous development of planning algorithms will drive innovation in the field of autonomous UAV drones, opening new possibilities for their use in constrained environments. Ultimately, the goal is to achieve fully autonomous UAV drones that can operate safely and effectively in any indoor setting, contributing to smarter and more automated systems.
