Home

Awesome

AM-Traj

Alternating Minimization Based Trajectory Generation for Quadrotor Aggressive Flight

Deprecated !!!

This repo is deprecated.

For local-planning, it is encouraged to use our EGO-Planner.

For general-purpose multicopter trajectory optimization, it is encouraged to check our solver GCOPTER if released.

0. About

AM-Traj is a C++11 header-only library for generating large-scale piecewise polynomial trajectories for aggressive autonomous flights, with highlights on its superior computational efficiency and simultaneous spatial-temporal optimality. Besides, an extremely fast feasibility checker is designed for various kinds of constraints. All components in this framework leverage the algebraic convenience of polynomial trajectory optimization problem, thus our method is capable of computing a spatial-temporal optimal trajectory with 60 pieces within 5ms, i.e., 150Hz at least. You just need to include "am_traj.hpp" and "root_finder.hpp" in your code. Please use the up-to-date master branch which may have a better performance than the one in our paper.

Author: Zhepei Wang and Fei Gao from the ZJU Fast Lab.

Related Papers:

Video Links: youtube or bilibili

<p align="center"> <img src="misc/cp.gif" width = "533" height = "300"/> </p> <p align="center"> <img src="misc/sv.gif" width = "427" height = "240"/> <img src="misc/fpv.gif" width = "427" height = "240"/> </p>

1. Features

2. Interface

Only three functions below are needed.

Constructor

AmTraj(double wT, double wA, double wJ, double mVr, double mAr, int mIts, double eps)

Inputs:

wT: Weight for the time regularization
wA: Weight for the integrated squared norm of acceleration
wJ: Weight for the integrated squared norm of jerk
mVr: Maximum velocity rate
mAr: Maximum acceleration rate
mIts: Maximum number of iterations in optimization
eps: Relative tolerance

Outputs:

An instance of AmTraj: An object used for trajectory generation

Example:

AmTraj amTrajOpt(1024.0, 32.0, 1.0, 7.0, 3.5, 32, 0.02);

Unconstrained Spatial-Temporal Optimization

Trajectory AmTraj::genOptimalTrajDT(const std::vector<Eigen::Vector3d> &wayPs, Eigen::Vector3d iniVel, Eigen::Vector3d iniAcc, Eigen::Vector3d finVel, Eigen::Vector3d finAcc) const

Inputs:

wayPs: Fixed waypoints for a trajectory
iniVel: Trajectory velocity at the first waypoint
iniAcc: Trajectory acceleration at the first waypoint
finVel: Trajectory velocity at the last waypoint
finAcc: Trajectory acceleration at the last waypoint

Outputs:

An instance of Trajectory: A trajectory with optimal coefficient matrices and optimal durations, on which constraints of maximum velocity/acceleration rate are not guaranteed

Example:

Eigen::Vector3d iV(2.0, 1.0, 0.0), fV(0.0, 0.0, 0.0)
Eigen::Vector3d iA(0.0, 0.0, 2.0), fA(0.0, 0.0, 0.0)
std::vector<Eigen::Vector3d> wPs;
wPs.emplace_back(0.0, 0.0, 0.0);
wPs.emplace_back(4.0, 2.0, 1.0);
wPs.emplace_back(9.0, 7.0, 5.0);
wPs.emplace_back(1.0, 3.0, 2.0);
Trajectory traj = amTrajOpt.genOptimalTrajDT(wPs, iV, iA, fV, fA);

Constrained Spatial-Temporal Optimization

Trajectory AmTraj::genOptimalTrajDTC(const std::vector<Eigen::Vector3d> &wayPs, Eigen::Vector3d iniVel, Eigen::Vector3d iniAcc, Eigen::Vector3d finVel, Eigen::Vector3d finAcc) const

Inputs:

wayPs: Fixed waypoints for a trajectory
iniVel: Trajectory velocity at the first waypoint
iniAcc: Trajectory acceleration at the first waypoint
finVel: Trajectory velocity at the last waypoint
finAcc: Trajectory acceleration at the last waypoint

Outputs:

An instance of Trajectory: A trajectory with optimal coefficient matrices and best time allocation, whose maximum velocity/acceleration rate are guaranteed to satisfy constraints

Example:

Eigen::Vector3d iV(2.0, 1.0, 0.0), fV(0.0, 0.0, 0.0)
Eigen::Vector3d iA(0.0, 0.0, 2.0), fA(0.0, 0.0, 0.0)
std::vector<Eigen::Vector3d> wPs;
wPs.emplace_back(0.0, 0.0, 0.0);
wPs.emplace_back(4.0, 2.0, 1.0);
wPs.emplace_back(9.0, 7.0, 5.0);
wPs.emplace_back(1.0, 3.0, 2.0);
Trajectory traj = amTrajOpt.genOptimalTrajDTC(wPs, iV, iA, fV, fA);

The Others

There are many useful functions in the header files. Use it by following their comments.

3. Performance

3.0 Performance over different feasibility checkers

<p align="center"> <img src="misc/comparefc.png" width = "496" height = "300"/> </p>

We compare our feasibility check method with Mueller's recursive bound check, Burri's analytical extrema check, as well as the widely used sampling-based check. In each case, 1000 trajectory pieces are randomly generated along with maximum velocity rate constraints to estimate average time consumption. As is shown in above figure, our method outperforms all other methods in computation speed because of its resolution independence and scalability with higher polynomial orders.

3.1 Performance over different trajectory optimizers

<p align="center"> <img src="misc/compareto.png" width = "700" height = "300"/> </p>

The benchmark is done as follows: We generate a sequence of waypoints by random walk, of which the step is uniformly distributed over [-3.0m, 8.0m] for each axis. The maximum speed and acceleration rates are set to 5.0m/s and 3.5m/s^2, respectively. The derivatives on the first and the last waypoints are set to zero. The objective function is set as wT=512.0, wA=0.0, wJ=1.0. For a given number of pieces, each method is applied to 1000 sequences of waypoints. The cost is then normalized by the cost of unconstrained case of our method. All comparisons are conducted on an Intel Core i7-8700 CPU under Linux environment.

We compare our method with Richter's method with time allocation optimized by NLopt (QP + NLOPT) and Mellinger's method with durations properly scaled using Liu's method (BGD + Time Scaling). As is shown in the figure above, our optimizer has the fastest speed and the lowest cost when constraints are taken into consideration.

4. Examples

Two examples are provided in this repository.

4.0 Example 0

Example 0 contains a simple comparison between the constrained case of our method against conventional method which uses heuristic time allocation along with time scaling. The lap time, maximum velocity/acceleration rate, cost function value, and visualization are provided.

<p align="center"> <img src="misc/visual.png" width = "463" height = "300"/> </p>

4.1 Example 1

Example 1 contains a complete global planner simulation procedure. In this example, we adopt an RRT* based waypoints selector proposed by Richter et al.. Based on the selector, we use our library to generate a optimal feasible trajectory. The whole planner is able to do global traejctory generation in real time.

<p align="center"> <img src="misc/example1viz.gif" width = "534" height = "300"/> </p> <p align="center"> <img src="misc/twowindows.png" width = "533" height = "300"/> </p>

First, we should keep the pygame window active by click it once. Then, press N on your keyboard to activate manual mode. Press W/A/S/D and Up/Down/Left/Right on your keyboard to control the white quadrotor's height/yaw and horizontal movement respectively. Please navigate the quadrotor to a safe region. After that, press M on your keyboary to enter auto mode such that global planner is activated.

To navigate the quadrotor to any region safely, you should click once the following button on tools bar of rviz.

<p align="center"> <img src="misc/navgbutton.png" width = "232" height = "74"/> </p>

Once the button is clicked, you can move your mouse arrow to any free region you want. Click the place and hold it, then a green arrow appears as is shown in the following figure. You can change the direction of the green arrow. It is worth noting that, the angle between this arrow and positive part of x-axis (red axis) decides the relative height you want the quadrotor to keep at this region. The arrow in figure below gives 60 degrees which means the desired height is 60/180*MapHeight.

<p align="center"> <img src="misc/click.png" width = "280" height = "210"/> </p>

Now unhold the click, the global planner will finds you an appropriate trajectory instantly. The quadrotor then tracks the trajectory.

<p align="center"> <img src="misc/track.png" width = "533" height = "300"/> </p>

5. Misc

6. Licence

The source code is released under GPLv3 license.

7. Maintaince

For any technical issues, please contact Zhepei WANG (wangzhepei@live.com) or Fei GAO (fgaoaa@zju.edu.cn).

For commercial inquiries, please contact Fei GAO (fgaoaa@zju.edu.cn).