|
6 | 6 | This is the Control Toolbox, an efficient C++ library for control, estimation, optimization and motion planning in robotics.
|
7 | 7 | Please find the documentation [here](https://adrlab.bitbucket.io/ct)
|
8 | 8 |
|
9 |
| -# Earlier Versions |
| 9 | +## Earlier Versions |
10 | 10 |
|
11 | 11 | Earlier versions up to v2.3 are hosted on bitbucket, they can be found at https://bitbucket.org/adrlab/ct/wiki/Home
|
12 | 12 |
|
13 |
| -# Licence Information |
14 | 13 |
|
| 14 | +## Overview |
| 15 | + |
| 16 | +This is the ADRL Control Toolbox ('CT'), an open-source C++ library for efficient modelling, control, |
| 17 | +estimation, trajectory optimization and model predictive control. The CT is applicable to a broad class of dynamic systems, but features additional modelling tools specially designed for robotics. This page outlines its general concept, its major building blocks and highlights selected application examples. |
| 18 | + |
| 19 | +The library contains several tools to design and evaluate controllers, model dynamical systems and solve optimal control problems. |
| 20 | +The CT was designed with the following features in mind: |
| 21 | + |
| 22 | + - **Systems and dynamics**: |
| 23 | + - intuitive modelling of systems governed by ordinary differential- or difference equations. |
| 24 | + |
| 25 | + - **Trajectory optimization, optimal control and (nonlinear) model predictive control**: |
| 26 | + - intuitive modelling of cost functions and constraints |
| 27 | + - common interfaces for optimal control solvers and nonlinear model predictive control |
| 28 | + - currently supported algorithms: |
| 29 | + - Single Shooting |
| 30 | + - iLQR |
| 31 | + - Gauss-Newton-Multiple-Shooting (GNMS) |
| 32 | + - Classical Direct Multiple Shooting (DMS) |
| 33 | + - standardized interfaces for the solvers |
| 34 | + - IPOPT (first and second order) |
| 35 | + - SNOPT |
| 36 | + - HPIPM |
| 37 | + - custom Riccati-solver |
| 38 | + |
| 39 | + - **Performance**: |
| 40 | + - solve large scale optimal control problems in MPC fashion. |
| 41 | + |
| 42 | + - **Robot Modelling, Rigid Body Kinematics and Dynamics**: |
| 43 | + - straight-forward interface to a state-of the art rigid body dynamics modelling tool. |
| 44 | + - implementation of a basic nonlinear-programming-based inverse kinematics solver. |
| 45 | + |
| 46 | + - **Automatic Differentiation**: |
| 47 | + - first- and second order automatic differentiation of arbitrary vector-valued functions including cost functions and constraints |
| 48 | + - automatic differentiation of rigid body dynamics |
| 49 | + - derivative code generation for maximum efficiency |
| 50 | + |
| 51 | + - **Simplicity**: |
| 52 | + - all algorithm flavors and solver backends are available through simple configuration files. |
| 53 | + |
| 54 | + |
| 55 | + |
| 56 | +## Robot Application Examples |
| 57 | + |
| 58 | +The Control Toolbox has been used for Hardware and Simulation control tasks on flying, walking and ground robots. |
| 59 | + |
| 60 | +[](https://www.youtube.com/embed/Y7-1CBqs4x4) |
| 61 | +[](https://www.youtube.com/embed/vuCSKtP67E4) |
| 62 | +[](https://www.youtube.com/embed/rWmw-ERGyz4) |
| 63 | +[](https://www.youtube.com/embed/rVu1L_tPCoM) |
| 64 | + |
| 65 | + |
| 66 | +## What is the CT? |
| 67 | + |
| 68 | +A common tasks for researchers and practitioners in both the control and the robotics communities |
| 69 | +is to model systems, implement equations of motion and design model-based controllers, estimators, |
| 70 | +planning algorithms, etc. |
| 71 | +Sooner or later, one is confronted with questions of efficient implementation, computing derivative |
| 72 | +information, formulating cost functions and constraints or running controllers in model-predictive |
| 73 | +control fashion. |
| 74 | + |
| 75 | +The Control Toolbox is specifically designed for these tasks. It is written entirely in C++ and has |
| 76 | +a strong focus on highly efficient code that can be run online (in the loop) on robots or other |
| 77 | +actuated hardware. A major contribution of the CT is are its implementations of optimal control |
| 78 | +algorithms, spanning a range from simple LQR reference implementations to constrained model predictive |
| 79 | +control. The CT supports Automatic Differentiation (Auto-Diff) and allows to generate derivative code |
| 80 | +for arbitrary scalar and vector-valued functions. |
| 81 | +We designed the toolbox with usability in mind, allowing users to apply advanced concepts such as |
| 82 | +nonlinear model predictive control (NMPC) or numerical optimal control easily and with minimal effort. |
| 83 | +While we provide an interface to a state-of-the art Auto-Diff compatible robot modelling software, all |
| 84 | +other modules are independent of the a particular modelling framework, allowing the code to be interfaced |
| 85 | +with existing C/C++ code or libraries. |
| 86 | + |
| 87 | +The CT has been successfully used in a variety of different projects, including a large number of |
| 88 | +hardware experiments, demonstrations and academic publications. |
| 89 | +Example hardware applications are online trajectory optimization with collision |
| 90 | +avoidance \cite giftthaler2017autodiff, trajectory optimization for Quadrupeds \cite neunert:2017:ral |
| 91 | +and mobile manipulators \cite giftthaler2017efficient as well as NMPC on ground robots \cite neunert2017mpc |
| 92 | +and UAVs \cite neunert16hexrotor. The project originated from research conducted at the Agile \& Dexterous |
| 93 | +Robotics Lab at ETH Zurich, but is continuously extended to cover more fields of applications and algorithms. |
| 94 | + |
| 95 | + |
| 96 | +## Scope of the CT |
| 97 | + |
| 98 | + Software is one of the key building blocks for robotic systems and there is a great effort |
| 99 | + in creating software tools and libraries for robotics. |
| 100 | + However, when it comes to control and especially Numerical Optimal Control, there are not |
| 101 | + many open source tools available that are both easy to use for fast development as well as |
| 102 | + efficient enough for online usage. |
| 103 | + While there exist mature toolboxes for Numerical Optimal Control and Trajectory Optimization, |
| 104 | + they are highly specialized, standalone tools that due not provide sufficient flexibility |
| 105 | + for other applications. Here is where the CT steps in. The CT has been designed from ground |
| 106 | + up to provide the tools needed for fast development and evaluation of control methods while |
| 107 | + being optimized for efficiency allowing for online operation. While the emphasis lies on control, |
| 108 | + the tools provided can also be used for simulation, estimation or optimization applications. |
| 109 | + |
| 110 | + In contrast to other robotic software, CT is not a rigid integrated application but can be |
| 111 | + seen quite literal as a toolbox: It offers a variety of tools which can be used and combined |
| 112 | + to solve a task at hand. While ease-of-use has been a major criteria during the design and |
| 113 | + application examples are provided, using CT still requires programming and control knowledge. |
| 114 | + However, it frees the users from implementing standard methods that require in-depth experience |
| 115 | + with linear algebra or numerical methods. Furthermore, by using common definitions and types, |
| 116 | + a seamless integration between different components such as systems, controllers or integrators |
| 117 | + is provided, enabling fast prototyping. |
| 118 | + |
| 119 | + |
| 120 | +## Design and Implementation |
| 121 | + |
| 122 | +The main focus of CT is efficiency, which is why it is fully implemented in C++. |
| 123 | +Since CT is designed as a toolbox rather than an integrated application, we tried to provide |
| 124 | +maximum flexibility to the users. Therefore, it is not tied to a specific middleware such as |
| 125 | +ROS and dependencies are kept at a minimum. The two essential dependencies for CT are |
| 126 | +<a href="http://eigen.tuxfamily.org" target="_blank">Eigen</a> and |
| 127 | +<a href="http://github.com/ethz-asl/kindr" target="_blank">Kindr</a> |
| 128 | +(which is based on Eigen). This Eigen dependency is intentional since Eigen |
| 129 | +is a defacto standard for linear algebra in C++, as it provides highly efficient implementations |
| 130 | +of standard matrix operations as well as more advanced linear algebra methods. |
| 131 | +Kindr is a header only Kinematics library which builds on top of it and provides data types |
| 132 | +for different rotation representations such as Quaternions, Euler angles or rotation matrices. |
| 133 | + |
| 134 | + |
| 135 | +## Structure and Modules of the CT |
| 136 | + |
| 137 | +The Control Toolbox consists of three main modules. The Core module (ct_core), the Optimal |
| 138 | +Control (ct_optcon) module and the rigid body dynamics (ct_rbd) module. |
| 139 | +There is a clear hierarchy between the modules. |
| 140 | +That means, the modules depend on each other in this order, e.g. you can use the core module |
| 141 | +without the optcon or rbd module. |
| 142 | + - The `core' module (ct_core) module provides general type definitions and mathematical tools. |
| 143 | +For example, it contains most data type definitions, definitions for systems and controllers, |
| 144 | +as well as basic functionality such as numerical integrators for differential equations. |
| 145 | + - The `optimal Control' module (ct_optcon) builds on top of the `core' module and adds |
| 146 | +infrastructure for defining and solving Optimal Control Problems. It contains the functionality |
| 147 | +for defining cost functions, constraints, solver backends and a general MPC wrapper. |
| 148 | + - The `rigid body dynamics' module (ct_rbd) provides tools for modelling Rigid Body Dynamics |
| 149 | +systems and interfaces with ct_core and ct_optcon data types. |
| 150 | + |
| 151 | +For testing as well as examples, we also provide the 'models' module (ct_models) which contains |
| 152 | +various robot models including a quadruped, a robotic arm, a normal quadrotor and a quadrotor |
| 153 | +with slung load. |
| 154 | + |
| 155 | +The four different main modules are detailed in the following. |
| 156 | + |
| 157 | + |
| 158 | +### ct_core |
| 159 | + |
| 160 | + - Definitions of fundamental types for **control** and simulation, such as dynamic systems |
| 161 | + (ct::core::System), states (ct::core::StateVector), controls (ct::core::Controller), or trajectories |
| 162 | + (ct::core::DiscreteTrajectoryBase). |
| 163 | + - **Numeric integration** (ct::core::Integrator) with various ODE solvers including fixed step |
| 164 | + (ct::core::IntegratorEuler, ct::core::IntegratorRK4) and variable step (ct::core::IntegratorRK5Variable, |
| 165 | + ct::core::ODE45) integrators, as well as symplectic (semi-implicit) integrators. |
| 166 | + - Numerical approximation of Trajectory **Sensitivities** (ct::core::Sensitivity , e.g. by forward-integrating |
| 167 | + variational differential equations) |
| 168 | + - Common **feedback controllers** (e.g. ct::core::PIDController) |
| 169 | + - Derivatives/Jacobians of general functions using **Numerical Differentiation** (ct::core::DerivativesNumDiff) |
| 170 | + or **Automatic-Differentiation** with code-generation (ct::core::DerivativesCppadCG) and just-in-time (JIT) |
| 171 | + compilation (ct::core::DerivativesCppadJIT) |
| 172 | + |
| 173 | + |
| 174 | +### ct_optcon (optimal control) |
| 175 | + |
| 176 | + - Definitions for **Optimal Control Problems** (ct::optcon::OptConProblem) and **Optimal Control Solvers** (ct::optcon::OptConSolver) |
| 177 | + - **CostFunction toolbox** allowing to construct cost functions from file and providing first-order and **second-order approximations**, see ct::optcon::CostFunction. |
| 178 | + - **Constraint toolbox** for formulating constraints of Optimal Control Problems, as well as automatically computing their Jacobians. |
| 179 | + - reference C++ implementations of the **Linear Quadratic Regulator**, infinite-horizon LQR and time-varying LQR (ct::optcon::LQR, ct::optcon::TVLQR) |
| 180 | + - **Riccati-solver** (ct::optcon::GNRiccatiSolver) for unconstrained linear-quadratic optimal control problems, interface to high-performance |
| 181 | + <a href="https://github.com/giaf/hpipm" target="_blank"> third-party Riccati-solvers</a> for constrained linear-quadratic optimal control problems |
| 182 | + - **iterative non-linear Optimal Control** solvers, i.e. Gauss-Newton solvers such as iLQR (ct::optcon::iLQR) and |
| 183 | + Gauss-Newton Multiple Shooting(ct::optcon::GNMS), constrained direct multiple-shooting (ct::optcon::DmsSolver) |
| 184 | + - Non-Linear **Model Predictive Control** (ct::optcon::MPC) |
| 185 | + - Definitions for Nonlinear Programming Problems (**NLPs**, ct::optcon::Nlp) and interfaces to third-party **NLP Solvers** |
| 186 | + (ct::optcon::SnoptSolver and ct::optcon::IpoptSolver) |
| 187 | + |
| 188 | + |
| 189 | +### ct_rbd (Rigid Body Dynamics) |
| 190 | + |
| 191 | + - Standard models for Rigid Body Dynamics |
| 192 | + - Definitions for the state of a Rigid Body System expressed as general coordinates (ct::rbd::RBDState) |
| 193 | + - Routines for different flavors of **Forward** and **Inverse Dynamics** (ct::rbd::Dynamics) |
| 194 | + - Rigid body and end-effector **kinematics** (ct::rbd::Kinematics) |
| 195 | + - Operational Space Controllers |
| 196 | + - Basic soft **auto-differentiable contact model** for arbitrary frames (ct::rbd::EEContactModel) |
| 197 | + - **Actuator dynamics** (ct::rbd::ActuatorDynamics) |
| 198 | + - Backend uses <a href="https://bitbucket.org/mfrigerio17/roboticscodegenerator/" target="_blank">RobCoGen</a> \cite frigerioCodeGen, |
| 199 | + a highly efficient Rigid Body Dynamics library |
| 200 | + |
| 201 | + |
| 202 | +### ct_models |
| 203 | + |
| 204 | + - Various standard models for testing and evaluation including UAVs (ct::models::Quadrotor), ground robots, |
| 205 | + legged robots (ct::models::HyQ), robot arms (ct::models::HyA), inverted pendulums etc. |
| 206 | + - Means of creating linear approximation of these models |
| 207 | + |
| 208 | + |
| 209 | +## How to get started |
| 210 | + |
| 211 | +To get started with the control toolbox, please build the repository documentation with doxygen and follow the "Getting Started" tutorial. |
| 212 | + |
| 213 | + |
| 214 | +## Support |
| 215 | +- contact the devs: control-toolbox-dev@googlegroups.com |
| 216 | + |
| 217 | + |
| 218 | +## Acknowledgements |
| 219 | + |
| 220 | +### Contributors |
| 221 | + - Markus Giftthaler |
| 222 | + - Michael Neunert |
| 223 | + - Markus Stäuble |
| 224 | + - Farbod Farshidian |
| 225 | + - Diego Pardo |
| 226 | + - Timothy Sandy |
| 227 | + - Jan Carius |
| 228 | + - Ruben Grandia |
| 229 | + - Hamza Merzic |
| 230 | + |
| 231 | +### Project Lead and Maintenance |
| 232 | + - Markus Giftthaler, markusgft (at) gmail (dot) com |
| 233 | + - Michael Neunert, neunertm (at) gmail (dot) com |
| 234 | + |
| 235 | +### Funding |
| 236 | +This software has been developed at the <a href="http://www.adrl.ethz.ch" target="_blank">Agile & Dexterous Robotics Lab</a> |
| 237 | +at <a href="http://www.ethz.ch/en" target="_blank">ETH Zurich</a>, Switzerland between 2014 and 2018. |
| 238 | +During that time, development has been made possible through financial support from the <a href="http://www.snf.ch/en/" target="_blank">Swiss National Science Foundation (SNF)</a> |
| 239 | +through a SNF Professorship award to Jonas Buchli and the National Competence Centers in Research (NCCR) |
| 240 | +<a href="https://www.nccr-robotics.ch/" target="_blank">Robotics</a> and <a href="http://www.dfab.ch/en/" target="_blank">Digital Fabrication</a>. |
| 241 | + |
| 242 | + |
| 243 | +## Licence Information |
| 244 | + |
| 245 | +The Control Toolbox is released under the |
| 246 | +<a href="https://choosealicense.com/licenses/bsd-2-clause/" target="_blank">BSD-2 clause license</a>. |
15 | 247 | Please see LICENCE.txt and NOTICE.txt
|
| 248 | + |
| 249 | + |
| 250 | +## How to cite the CT |
| 251 | + |
| 252 | + @misc{adrlCT, |
| 253 | + author = {Giftthaler, Markus and Neunert, Michael and {St\"auble}, Markus and Buchli, Jonas}, |
| 254 | + booktitle = {2018 IEEE International Conference on Simulation, Modeling, and Programming for Autonomous Robots (SIMPAR)}, |
| 255 | + author = {Giftthaler, Markus and Neunert, Michael and {St\"auble}, Markus and Buchli, Jonas}, |
| 256 | + title = "The {Control Toolbox} - An Open-Source {C++} Library for Robotics, Optimal and Model Predictive Control", |
| 257 | + year = 2018, |
| 258 | + pages ={123-129}, |
| 259 | + doi ={10.1109/SIMPAR.2018.8376281}, |
| 260 | + month ={May}, |
| 261 | + number ={}, |
| 262 | + volume ={}, |
| 263 | + } |
| 264 | + |
| 265 | + |
| 266 | +## Related Publications |
| 267 | + |
| 268 | +This toolbox has been used in, or has helped to realize the following academic publications: |
| 269 | + |
| 270 | +- Markus Giftthaler, Michael Neunert, Markus Stäuble and Jonas Buchli. |
| 271 | +“The Control Toolbox - An Open-Source C++ Library for Robotics, Optimal and Model Predictive Control”. |
| 272 | +IEEE Simpar 2018 (Best Student Paper Award). |
| 273 | +<a href="https://arxiv.org/abs/1801.04290" target="_blank">arXiv preprint</a> |
| 274 | + |
| 275 | +- Markus Giftthaler, Michael Neunert, Markus Stäuble, Jonas Buchli and Moritz Diehl. |
| 276 | +“A Family of iterative Gauss-Newton Shooting Methods for Nonlinear Optimal Control”. |
| 277 | +IROS 2018. |
| 278 | +<a href="https://arxiv.org/abs/1711.11006" target="_blank">arXiv preprint</a> |
| 279 | + |
| 280 | +- Jan Carius, René Ranftl, Vladlen Koltun and Marco Hutter. |
| 281 | +"Trajectory Optimization with Implicit Hard Contacts." |
| 282 | +IEEE Robotics and Automation Letters 3, no. 4 (2018): 3316-3323. |
| 283 | + |
| 284 | +- Michael Neunert, Markus Stäuble, Markus Giftthaler, Dario Bellicoso, Jan Carius, Christian Gehring, |
| 285 | +Marco Hutter and Jonas Buchli. |
| 286 | +“Whole Body Model Predictive Control Through Contacts For Quadrupeds”. |
| 287 | +IEEE Robotics and Automation Letters, 2017. |
| 288 | +<a href="https://arxiv.org/abs/1712.02889" target="_blank">arXiv preprint</a> |
| 289 | + |
| 290 | +- Markus Giftthaler and Jonas Buchli. |
| 291 | +“A Projection Approach to Equality Constrained Iterative Linear Quadratic Optimal Control”. |
| 292 | +2017 IEEE-RAS International Conference on Humanoid Robots, November 15-17, Birmingham, UK. |
| 293 | +<a href="http://ieeexplore.ieee.org/document/8239538/" target="_blank">IEEE Xplore</a> |
| 294 | + |
| 295 | +- Markus Giftthaler, Michael Neunert, Markus Stäuble, Marco Frigerio, Claudio Semini and Jonas Buchli. |
| 296 | +“Automatic Differentiation of Rigid Body Dynamics for Optimal Control and Estimation”, |
| 297 | +Advanced Robotics, SIMPAR special issue. November 2017. |
| 298 | +<a href="https://arxiv.org/abs/1709.03799" target="_blank">arXiv preprint</a> |
| 299 | + |
| 300 | +- Michael Neunert, Markus Giftthaler, Marco Frigerio, Claudio Semini and Jonas Buchli. |
| 301 | +“Fast Derivatives of Rigid Body Dynamics for Control, Optimization and Estimation”, |
| 302 | +2016 IEEE International Conference on Simulation, Modelling, and Programming for Autonomous Robots, |
| 303 | +San Francisco. (Best Paper Award). |
| 304 | +<a href="http://ieeexplore.ieee.org/document/7862380/" target="_blank">IEEE Xplore</a> |
| 305 | + |
| 306 | +- Michael Neunert, Farbod Farshidian, Alexander W. Winkler, Jonas Buchli |
| 307 | +"Trajectory Optimization Through Contacts and Automatic Gait Discovery for Quadrupeds", |
| 308 | +IEEE Robotics and Automation Letters, |
| 309 | +<a href="http://ieeexplore.ieee.org/document/7845678/" target="_blank">IEEE Xplore</a> |
| 310 | + |
| 311 | +- Michael Neunert, Cédric de Crousaz, Fadri Furrer, Mina Kamel, Farbod Farshidian, Roland Siegwart, Jonas Buchli. |
| 312 | +"Fast nonlinear model predictive control for unified trajectory optimization and tracking", |
| 313 | +2016 IEEE International Conference on Robotics and Automation (ICRA), |
| 314 | +<a href="http://ieeexplore.ieee.org/document/7487274/" target="_blank">IEEE Xplore</a> |
| 315 | + |
| 316 | +- Markus Giftthaler, Farbod Farshidian, Timothy Sandy, Lukas Stadelmann and Jonas Buchli. |
| 317 | +“Efficient Kinematic Planning for Mobile Manipulators with Non-holonomic Constraints Using Optimal Control”, |
| 318 | +IEEE International Conference on Robotics and Automation, 2017, Singapore. |
| 319 | +<a href="https://arxiv.org/abs/1701.08051" target="_blank">arXiv preprint</a> |
| 320 | + |
| 321 | +- Markus Giftthaler, Timothy Sandy, Kathrin Dörfler, Ian Brooks, Mark Buckingham, Gonzalo Rey, |
| 322 | +Matthias Kohler, Fabio Gramazio and Jonas Buchli. |
| 323 | +“Mobile Robotic Fabrication at 1:1 scale: the In situ Fabricator”. Construction Robotics, Springer Journal no. 41693 |
| 324 | +<a href="https://arxiv.org/abs/1701.03573" target="_blank">arXiv preprint</a> |
| 325 | + |
| 326 | +- Timothy Sandy, Markus Giftthaler, Kathrin Dörfler, Matthias Kohler and Jonas Buchli. |
| 327 | +“Autonomous Repositioning and Localization of an In situ Fabricator”, |
| 328 | +IEEE International Conference on Robotics and Automation 2016, Stockholm, Sweden. |
| 329 | +<a href="http://ieeexplore.ieee.org/document/7487449/" target="_blank">IEEE Xplore</a> |
| 330 | + |
| 331 | +- Michael Neunert, Farbod Farshidian, Jonas Buchli (2014). Adaptive Real-time Nonlinear Model Predictive Motion Control. |
| 332 | +In IROS 2014 Workshop on Machine Learning in Planning and Control of Robot Motion |
| 333 | +<a href="http://www.adrl.ethz.ch/archive/p_14_mlpc_mpc_rezero.pdf" target="_blank">preprint</a> |
0 commit comments