Skip to content

Commit

Permalink
readme modified
Browse files Browse the repository at this point in the history
  • Loading branch information
icsl-Jeon committed Mar 22, 2020
1 parent 76655b9 commit 954b59d
Showing 1 changed file with 92 additions and 7 deletions.
99 changes: 92 additions & 7 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<img src= "https://github.com/icsl-Jeon/traj_gen/blob/master/img/logo2.png" width="300" >

## traj_gen : a continuous trajectory generation with simple API (C++/Matlab)
### Version 2.0.1 (Mar 18, 2020)
### Version 2.1.0 (Mar 22, 2020)
<img src = "https://travis-ci.com/icsl-Jeon/traj_gen.svg?branch=master"> <img src = "https://img.shields.io/github/license/Naereen/StrapDown.js.svg">
<img src=https://img.shields.io/github/v/release/icsl-Jeon/traj_gen?include_prereleases >

Expand All @@ -12,9 +12,8 @@
<p align = "center">
<img src= "https://github.com/icsl-Jeon/traj_gen/blob/master/img/tutorial.gif">
</p>

*traj_gen* is a continuous trajectory generation package where <u>high order derivatives</u>
along the trajectory are minimized while satisfying waypoints (equality) and axis-parallel box constraint (inequality). The objective and constraints are formulated in *quadratic programming* (QP) to cater the real-time performance. The whole code is written in C++ and Matlab (go to [submodule](https://github.com/icsl-Jeon/traj_gen-matlab) for its API). The C++ API was tested in Ubuntu 14.04/16.04/18.04. ROS wrapper is still developing to provide similar interface with [version 1](https://github.com/icsl-Jeon/traj_gen/tree/deprecated-version1).
along the trajectory are minimized while satisfying waypoints (equality) and axis-parallel box constraint (inequality). The objective and constraints are formulated in *quadratic programming* (QP) to cater the real-time performance. The whole code is written in C++ and Matlab (go to [submodule](https://github.com/icsl-Jeon/traj_gen-matlab) for its API). The C++ API was tested in Ubuntu 14.04/16.04/18.04.

- To parameterize a trajectory, we use two types of curve: 1) **piecewise-polynomials** [1,2] and 2) **a sequence of points** [3].
The difference is optimization variables.
Expand All @@ -26,8 +25,8 @@ The difference is optimization variables.
and *loose-pin* denotes a axis-parallel box constraint. The pin is a triplets (time (t), order of derivatives (d), value (x)) where x is
a vector in case of fix-pin while two vectors [xl xu] for the loose-pin.

- We implemented traj_gen in Matlab and C++(upcoming ~ the end of Mar). In case of 2D trajectory generation in Matlab, we provide interactive pin selection (see poly_example/main2D).
Also, we plan to provide ROS support such as the [previous version](https://github.com/icsl-Jeon/traj_gen)
- We implemented traj_gen in Matlab and C++. In case of 2D trajectory generation in Matlab, we provide interactive pin selection (see poly_example/main2D).
Also, we plan to provide ROS support (~end of Mar) such as the [previous version](https://github.com/icsl-Jeon/traj_gen)


## Getting started
Expand All @@ -46,7 +45,7 @@ Also, we plan to provide ROS support such as the [previous version](https://gith
$ mkdir build && cd build
$ cmake .. -DCMAKE_CXX_FLAGS=-fPIC
$ sudo make install
```
```
- **Build traj_gen (C++)**
```
$ git clone https://github.com/icsl-Jeon/traj_gen.git
Expand All @@ -64,6 +63,9 @@ Also, we plan to provide ROS support such as the [previous version](https://gith
$ ./test_pin
```
### 2. C++ API quick start

### (1) Basic example (PolyTrajGen class)

```cpp
#include <traj_gen2/TrajGen.hpp>
#include <iostream>
Expand Down Expand Up @@ -110,7 +112,83 @@ int main(){

```



### (2) Advanced example (PolyTrajGen + OptimTrajGen)

```cpp
#include <traj_gen2/TrajGen.hpp>
#include <iostream>
#include <chrono>

using namespace trajgen;
using namespace Eigen;
using Type = double ;

int main(){
// 1. Prameter setting
// common
const int dim = 3;
time_knots<Type> ts{0,2,4,7};
Vector<Type,3> objWeights(0,1,1);

// polyTrajGen
uint poly_order = 8, max_conti = 4;
PolyParam pp(poly_order,max_conti,ALGORITHM::END_DERIVATIVE); // or ALGORITHM::POLY_COEFF
// optimTrajGen
Type pntDensity = 5;

// 2. Pin
// 2.1 FixPin
FixPin<Type,dim> x1(0.0f,0,Vector<Type,dim>(0,0,0));
FixPin<Type,dim> x2(2.0f,0,Vector<Type,dim>(2,-1,2));
FixPin<Type,dim> x3(4.0f,0,Vector<Type,dim>(5,3,4));
FixPin<Type,dim> x4(7.0f,0,Vector<Type,dim>(7,-5,5));

FixPin<Type,dim> xdot0(0.0f,1,Vector<Type,dim>(0,0,0));
FixPin<Type,dim> xddot0(0.0f,2,Vector<Type,dim>(0,0,0));

// 2.2 LoosePin
LoosePin<Type,dim> passCube(3.0f,0,Vector<Type,dim>(3,-3,1),Vector<Type,dim>(4.2,-2,2));

std::vector<Pin<Type,dim>*> pinSet{&x1,&x2,&x3,&x4,&xdot0,&xddot0,&passCube}; // to prevent downcasting slicing, vector of pointers

// Let's test the two trajGen class
TrajGen<Type,dim>** pTrajGenSet = new TrajGen<Type,dim>*[2];
pTrajGenSet[0] = new PolyTrajGen<Type,dim>(ts,pp);
pTrajGenSet[1] = new OptimTrajGen<Type,dim>(ts,pntDensity);
bool verbose = false;
bool isSolved = false;
string TrajGenClass[2] = {"PolyTraj","OptimTraj"};

Type t_eval = 3; d_order d_eval = 1;

for (uint i = 0 ; i <2 ; i++) {
auto begin = std::chrono::steady_clock::now();
pTrajGenSet[i]->setDerivativeObj(objWeights);
pTrajGenSet[i]->addPinSet(pinSet);
isSolved = pTrajGenSet[i]->solve(verbose);
printf("For %s, The evaluated value for (t=%.2f, d=%d) : ",TrajGenClass[i].c_str(),t_eval,d_eval);
if (isSolved)
cout << pTrajGenSet[i]->eval(t_eval,d_eval).transpose() << endl;
else
cout << "Failed. " << endl;

auto end= std::chrono::steady_clock::now();

std::cout << "Total time : " <<
std::chrono::duration_cast<std::chrono::microseconds>(end - begin).count()*1e-3 << "[ms]" << std::endl;
}
return 0;

}

```



### 3. Using traj_gen in your cmake project (CMakeLists.txt)

```
find_package(TrajGen REQUIRED)
...
Expand All @@ -136,11 +214,18 @@ target_link_libraries( your_exe .... traj_gen )

- *Maximum continuity* : the maximally imposed continuity order between neighboring segements. Higher value of this parameter enhances the quality of smoothness. However, too high value of this value restricts the dof for optimization, downgrading the opitimization result.


- **optimTrajGen**
- *Point density* : the number of posed points per time [s]. For long-ranged trajectory, thus, the total number of variables will increase leading to the burden of the optimization.

### Public methods

- Please run the following command to open the dedicated doxygen:

```
firefox cpp/docs/html/index.html
```



### Reference

Expand Down

0 comments on commit 954b59d

Please sign in to comment.