Skip to content

Commit

Permalink
Improve doxygen (#26)
Browse files Browse the repository at this point in the history
* add overview on main doxygen landing
* add doxygen groups to variables/constraints/costs
* add parameter explanation
  • Loading branch information
awinkler authored Jul 12, 2018
1 parent 59277d8 commit f738737
Show file tree
Hide file tree
Showing 47 changed files with 366 additions and 39 deletions.
2 changes: 1 addition & 1 deletion CONTRIBUTING.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@

# Contributing to <img src="https://i.imgur.com/zm2nwF7.png" width="15%"/>
# Contributing to towr

:+1::tada: First off, thanks for taking the time to contribute! :tada::+1:

Expand Down
11 changes: 8 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -98,13 +98,18 @@ We provide a [ROS]-wrapper for the pure cmake towr library, which adds a keyboar
```bash
roslaunch towr_ros towr_ros.launch
```
Click in the xterm terminal and hit 'o'.
Click in the xterm terminal and hit 'o'.

[![Documentation](https://img.shields.io/badge/docs-generated-brightgreen.svg)](http://docs.ros.org/kinetic/api/towr/html/)
For more detailed information on the parameters and how to tune them according to your problem, please see the
doxygen [documentation](http://docs.ros.org/kinetic/api/towr/html/).

[<img src="https://i.imgur.com/LNuyEIn.gif" />](https://www.youtube.com/embed/7dP_QTPOyQ8?rel=0&autoplay=1)


## Publications
The theory behind this code can be found in this paper:

A. W. Winkler, D. Bellicoso, M. Hutter, J. Buchli, [Gait and Trajectory Optimization for Legged Systems through Phase-based End-Effector Parameterization](https://awinkler.github.io/publications), IEEE Robotics and Automation Letters (RA-L), 2018:

@article{winkler18,
Expand All @@ -124,13 +129,14 @@ A. W. Winkler, D. Bellicoso, M. Hutter, J. Buchli, [Gait and Trajectory Optimiza
## Authors
[Alexander W. Winkler](http://awinkler.me) - Initial Work/Maintainer

The work was carried out at the following institutions:

[<img src="https://i.imgur.com/aGOnNTZ.png" height="45" />](https://www.ethz.ch/en.html "ETH Zurich") &nbsp; &nbsp; &nbsp; &nbsp; [<img src="https://i.imgur.com/uCvLs2j.png" height="45" />](http://www.adrl.ethz.ch/doku.php "Agile and Dexterous Robotics Lab") &nbsp; &nbsp; &nbsp; &nbsp;[<img src="https://i.imgur.com/gYxWH9p.png" height="45" />](http://www.rsl.ethz.ch/ "Robotic Systems Lab")



## Contributing
We love pull request, whether its new constraint formulations, additional robot models, bug fixes, unit tests or updating the documentation. Please have a look at [CONTRIBUTING.md](CONTRIBUTING.md) for more information.

See here the list of [contributors](https://github.com/ethz-adrl/towr/graphs/contributors) who participated in this project.


Expand Down Expand Up @@ -159,4 +165,3 @@ To report bugs, request features or ask questions, please have a look at [CONTRI
[catkin]: http://wiki.ros.org/catkin
[catkin tools]: http://catkin-tools.readthedocs.org/
[Eigen]: http://eigen.tuxfamily.org
[Fa2png]: http://fa2png.io/r/font-awesome/link/
2 changes: 2 additions & 0 deletions towr/.gitignore
Original file line number Diff line number Diff line change
@@ -1 +1,3 @@
build
doc/html/*
doc/manifest.yaml
Binary file added towr/doc/figures/towr_motion_snaps.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added towr/doc/figures/towr_problem.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added towr/doc/figures/towr_problem_with_code.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
83 changes: 83 additions & 0 deletions towr/doc/mainpage.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
TOWR - Trajectory Optimizer for Walking Robots {#mainpage}
---------------------

| *TOWR - A light-weight and extensible C++ library for trajectory optimization for legged robots.* | |
| -------|------ |
| <img src="../figures/towr_motion_snaps.png" width="700px"/> | |

This [Eigen]-based library implements variables, costs and constraints that can be
used to formulate and solve a legged locomotion optimization problem.
It has been used to generate a variety of motions such as monoped hopping,
biped walking, or a complete quadruped trotting cycle, while optimizing over
the gait and step durations in less than 100ms ([paper](https://ieeexplore.ieee.org/document/8283570/)).

Features:

* Inuitive formulations of variables, cost and constraints using [Eigen].
* [ifopt] allows to choose between [Ipopt] or [Snopt] to solve the NLP.
* fast performance due to Eigen sparse matrix exploitation.
* light-weight ([~6k lines](https://i.imgur.com/gP3gv34.png) of code) makes it easy to use and extend with own formulations.
* elegant rviz visualization of motion plans using [xpp].
* [catkin] integration (optional).


[TOC]

Install {#install}
========================
In case the binaries for you ROS distro don't exist, for more detailed
instructions as well as all dependencies, please checkout the
github
<a href="https://github.com/ethz-adrl/towr/blob/master/README.md">
README.md
</a>. Shortcut:
\code{.sh}
sudo apt-get install ros-<ros-distro>-towr_ros
\endcode



Run {#run}
=========================
To run the code, type
\code{.sh}
roslaunch towr_ros towr_ros.launch
\endcode


Tune {#tune}
==========================
See [parameters.h](structtowr_1_1Parameters.html#details) for
an explanation in how to tune the optimization problem.
The number of parameters to tune is relatively small (~10), however, they
do have a large impact on speed and convergence of the optimizer.


Paper {#paper}
=======================
It is helpful to read up on the theory underlying this code, which is explained
in this paper
[DOI: 10.1109/LRA.2018.2798285](https://doi.org/10.1109/LRA.2018.2798285).


Contribute {#contribute}
==========================
We love pull requests. Please see
<a href="https://github.com/ethz-adrl/towr/blob/master/CONTRIBUTING.md">
CONTRIBUTING.md
</a> if you want to contribute.
See here the list of
[contributors](https://github.com/ethz-adrl/towr/graphs/contributors)
who participated in this project.


Authors {#authors}
=======================
[Alexander W. Winkler](http://awinkler.me) - Initial Developer & Maintainence


[ROS]: http://www.ros.org
[xpp]: http://wiki.ros.org/xpp
[catkin]: http://wiki.ros.org/catkin
[Eigen]: http://eigen.tuxfamily.org

2 changes: 2 additions & 0 deletions towr/doc/rosdoc.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
- builder: doxygen
file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox *.md'
4 changes: 3 additions & 1 deletion towr/include/towr/constraints/base_motion_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,9 @@ namespace towr {
* @brief Keeps the 6D base motion in a specified range.
*
* In general this constraint should be avoided, since a similar affect can be
* achieved with @ref RangeOfMotion.
* achieved with RangeOfMotionConstraint.
*
* @ingroup Constraints
*/
class BaseMotionConstraint : public TimeDiscretizationConstraint {
public:
Expand Down
12 changes: 8 additions & 4 deletions towr/include/towr/constraints/dynamic_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,12 +49,16 @@ namespace towr {
* defined by the system dynamics.
*
* The physics-based acceleration is influenced by the robot state as
* xdd(t) = f(x(t), xd(t), f(t))
*
* xdd(t) = f(x(t), xd(t), f(t))
*
* The constraint of the optimization variables w is then:
* g(t) = acc_spline(t) - xdd(t)
* = acc_spline(t) - xdd(x(t), xd(t), f(t))
* = acc_spline(w) - xdd(w)
*
* g(t) = acc_spline(t) - xdd(t)
* = acc_spline(t) - xdd(x(t), xd(t), f(t))
* = acc_spline(w) - xdd(w)
*
* @ingroup Constraints
*/
class DynamicConstraint : public TimeDiscretizationConstraint {
public:
Expand Down
2 changes: 2 additions & 0 deletions towr/include/towr/constraints/force_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,8 @@ namespace towr {
*
* Attention: Constraint is enforced only at the spline nodes. In between
* violations of this constraint can occur.
*
* @ingroup Constraints
*/
class ForceConstraint : public ifopt::ConstraintSet {
public:
Expand Down
2 changes: 2 additions & 0 deletions towr/include/towr/constraints/linear_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,8 @@ namespace towr {

/**
* @brief Calculates the constraint violations for linear constraints.
*
* @ingroup Constraints
*/
class LinearEqualityConstraint : public ifopt::ConstraintSet {
public:
Expand Down
2 changes: 2 additions & 0 deletions towr/include/towr/constraints/range_of_motion_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,8 @@ namespace towr {
* This constraint calculates the position of of the contact expressed in the
* current CoM frame and constrains it to lie in a box around the nominal/
* natural contact position for that leg.
*
* @ingroup Constraints
*/
class RangeOfMotionConstraint : public TimeDiscretizationConstraint {
public:
Expand Down
2 changes: 2 additions & 0 deletions towr/include/towr/constraints/spline_acc_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@ namespace towr {
* This is used to restrict jumps in linear and angular base accelerations,
* since this would require jumps in foot positions or endeffector forces,
* which aren't allowed in our formulation.
*
* @ingroup Constraints
*/
class SplineAccConstraint : public ifopt::ConstraintSet {
public:
Expand Down
2 changes: 2 additions & 0 deletions towr/include/towr/constraints/swing_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@ namespace towr {
* leaves the e.g. range-of-motion in between nodes. This constraint can also
* be used to force a leg lift. However, it is cleanest if the optimization
* can be performed without this heuristic constraint.
*
* @ingroup Constraints
*/
class SwingConstraint : public ifopt::ConstraintSet {
public:
Expand Down
2 changes: 2 additions & 0 deletions towr/include/towr/constraints/terrain_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,8 @@ namespace towr {
* lifting during swing-phase. This is convenient.
*
* Attention: This is enforced only at the spline nodes.
*
* @ingroup Constraints
*/
class TerrainConstraint : public ifopt::ConstraintSet {
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@ namespace towr {
* @ref RangeOfMotion, or @ref DynamicConstraint at specific times t along
* the trajectory. This class is responsible for building the overall
* Jacobian from the individual Jacobians at each time instance.
*
* @ingroup Constraints
*/
class TimeDiscretizationConstraint : public ifopt::ConstraintSet {
public:
Expand Down
2 changes: 2 additions & 0 deletions towr/include/towr/constraints/total_duration_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,8 @@ namespace towr {
* Attention: At this point last phase duration is not an optimization variable
* and a way should be found to optimize over all phases while setting the
* total duration by constraint and not through hard parameterization.
*
* @ingroup Constraints
*/
class TotalDurationConstraint : public ifopt::ConstraintSet {
public:
Expand Down
2 changes: 2 additions & 0 deletions towr/include/towr/costs/node_cost.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@ namespace towr {

/**
* @brief Assigns a cost to node values.
*
* @ingroup Costs
*/
class NodeCost : public ifopt::CostTerm {
public:
Expand Down
20 changes: 16 additions & 4 deletions towr/include/towr/costs/soft_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,23 @@ namespace towr {
* @brief Converts a constraint to a cost by weighing the quadratic violations.
*
* Let constraint g(x) \in R^m with upper bound b_u and lower bound b_l.
* Let g'(x) = g(x) - 0.5(b_u+b_l) = g(x) - b
* And it's derivative dg'(x)/dx = J(x).
* Define a cost as c(x) = 0.5 * g'^T * W * g', where W = diag(w1,...,wm).
* Let
*
* g'(x) = g(x) - 0.5(b_u+b_l) = g(x) - b
*
* And it's derivative
*
* dg'(x)/dx = J(x).
*
* Define a cost as
*
* c(x) = 0.5 * g'^T * W * g', where W = diag(w1,...,wm).
*
* Then the gradient of the cost is defined as:
* dc(x)/dx = (g'(x)^T * W * J)^T = J^T * W * (g(x)-b).
*
* dc(x)/dx = (g'(x)^T * W * J)^T = J^T * W * (g(x)-b).
*
* @ingroup Costs
*/
class SoftConstraint : public ifopt::Component {
public:
Expand Down
2 changes: 2 additions & 0 deletions towr/include/towr/models/centroidal_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,8 @@ namespace towr {
* all quantities in Cartesian space.
*
* \sa https://en.wikipedia.org/wiki/Newton%E2%80%93Euler_equations
*
* @ingroup Robots
*/
class CentroidalModel : public DynamicModel {
public:
Expand Down
2 changes: 2 additions & 0 deletions towr/include/towr/models/dynamic_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@ namespace towr {
* Currently, only @ref CentroidalModel is implemented, but this can be
* extended in the future to also incorporate full rigid body dynamics. This
* interface to the solver should remain the same.
*
* @ingroup Robots
*/
class DynamicModel {
public:
Expand Down
6 changes: 5 additions & 1 deletion towr/include/towr/models/examples/anymal_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,10 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

namespace towr {

/**
* \addtogroup Robots
* @{
*/
class AnymalKinematicModel : public KinematicModel {
public:
AnymalKinematicModel () : KinematicModel(4)
Expand All @@ -61,8 +65,8 @@ class AnymalDynamicModel : public CentroidalModel {
0.946438, 1.94478, 2.01835, 0.000938112, -0.00595386, -0.00146328,
4) {}
};
/** @}*/

} // namespace towr


#endif /* TOWR_TOWR_ROS_INCLUDE_TOWR_ROS_ANYMAL_MODEL_H_ */
5 changes: 5 additions & 0 deletions towr/include/towr/models/examples/biped_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,10 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

namespace towr {

/**
* \addtogroup Robots
* @{
*/
class BipedKinematicModel : public KinematicModel {
public:
BipedKinematicModel () : KinematicModel(2)
Expand All @@ -58,6 +62,7 @@ class BipedDynamicModel : public CentroidalModel {
1.209,5.583,6.056,0.005,-0.190,-0.012,
2) {}
};
/** @}*/

} /* namespace towr */

Expand Down
6 changes: 5 additions & 1 deletion towr/include/towr/models/examples/hyq_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,10 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

namespace towr {

/**
* \addtogroup Robots
* @{
*/
class HyqKinematicModel : public KinematicModel {
public:
HyqKinematicModel () : KinematicModel(4)
Expand All @@ -53,13 +57,13 @@ class HyqKinematicModel : public KinematicModel {
}
};


class HyqDynamicModel : public CentroidalModel {
public:
HyqDynamicModel() : CentroidalModel(83,
4.26, 8.97, 9.88, -0.0063, 0.193, 0.0126,
4) {}
};
/** @}*/

} /* namespace towr */

Expand Down
7 changes: 5 additions & 2 deletions towr/include/towr/models/examples/monoped_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,10 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

namespace towr {

/**
* \addtogroup Robots
* @{
*/
class MonopedKinematicModel : public KinematicModel {
public:
MonopedKinematicModel () : KinematicModel(1)
Expand All @@ -52,8 +56,7 @@ class MonopedDynamicModel : public CentroidalModel {
1.2, 5.5, 6.0, 0.0, -0.2, -0.01, // base inertia
1) {} // number of endeffectors
};


/** @}*/

} /* namespace towr */

Expand Down
2 changes: 2 additions & 0 deletions towr/include/towr/models/kinematic_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@ namespace towr {
*
* This class is mainly used to formulate the @ref RangeOfMotionConstraint,
* restricting each endeffector to stay inside it's kinematic range.
*
* @ingroup Robots
*/
class KinematicModel {
public:
Expand Down
Loading

0 comments on commit f738737

Please sign in to comment.