├── src ├── robot_controllers │ ├── high │ │ ├── Dummy.conf │ │ ├── ForceModDS.cpp │ │ ├── ForceModDS.hpp │ │ ├── LinearDS.hpp │ │ ├── CMakeLists.txt │ │ └── LinearDS.cpp │ ├── low │ │ ├── Dummy.conf │ │ ├── Pid.hpp │ │ ├── PassiveDS.hpp │ │ ├── CMakeLists.txt │ │ ├── PassiveDS.cpp │ │ └── Pid.cpp │ ├── configure.h.cmake │ ├── utils │ │ ├── math.hpp │ │ └── math.cpp │ ├── AbstractController.cpp │ ├── SumController.hpp │ ├── CascadeController.hpp │ ├── CMakeLists.txt │ ├── CascadeController.cpp │ ├── SumController.cpp │ └── AbstractController.hpp ├── CMakeLists.txt └── examples │ ├── CMakeLists.txt │ └── linear_test.cpp ├── .gitignore ├── CONTRIBUTING.md ├── README.md ├── CMakeLists.txt ├── add_license.py └── LICENSE /src/robot_controllers/high/Dummy.conf: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/robot_controllers/low/Dummy.conf: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/robot_controllers/configure.h.cmake: -------------------------------------------------------------------------------- 1 | #define ROBOT_CONTROLLERS_PLUGINS_DIR "${ROBOT_CONTROLLERS_PLUGINS_DIR}" -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # Prerequisites 2 | *.d 3 | 4 | # Compiled Object files 5 | *.slo 6 | *.lo 7 | *.o 8 | *.obj 9 | 10 | # Precompiled Headers 11 | *.gch 12 | *.pch 13 | 14 | # Compiled Dynamic libraries 15 | *.so 16 | *.dylib 17 | *.dll 18 | 19 | # Fortran module files 20 | *.mod 21 | *.smod 22 | 23 | # Compiled Static libraries 24 | *.lai 25 | *.la 26 | *.a 27 | *.lib 28 | 29 | # Executables 30 | *.exe 31 | *.out 32 | *.app 33 | 34 | # VSCode folder 35 | .vscode 36 | 37 | # build folder 38 | build 39 | 40 | # macOS files 41 | *.DS_Store 42 | -------------------------------------------------------------------------------- /src/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #| 2 | #| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | #| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | #| Bernardo Fichera 5 | #| email: costashatz@gmail.com 6 | #| bernardo.fichera@epfl.ch 7 | #| website: lasa.epfl.ch 8 | #| 9 | #| This file is part of robot_controllers. 10 | #| 11 | #| robot_controllers is free software: you can redistribute it and/or modify 12 | #| it under the terms of the GNU General Public License as published by 13 | #| the Free Software Foundation, either version 3 of the License, or 14 | #| (at your option) any later version. 15 | #| 16 | #| robot_controllers is distributed in the hope that it will be useful, 17 | #| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | #| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | #| GNU General Public License for more details. 20 | #| 21 | add_subdirectory(robot_controllers) 22 | add_subdirectory(examples) -------------------------------------------------------------------------------- /CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Bug reports, feature requests or code contributions are always very welcome. 2 | 3 | To make things easier, here are a few tips: 4 | 5 | Reporting bugs, requesting features 6 | ----------------------------------- 7 | 8 | - Best way to report bugs and request new features is to use GitHub 9 | [Issues](https://github.com/epfl-lasa/robot_controllers/issues), but you can contact the maintainers also any other way — see the [README](README.md) for details. 10 | 11 | Code contribution 12 | ----------------- 13 | 14 | - Best way to contribute is using GitHub [Pull Requests](https://github.com/epfl-lasa/robot_controllers/pulls) 15 | — fork the repository and make a pull request from a feature branch. You can also send patches via e-mail or contact the maintainers in any other way — see the [README](README.md) for details. 16 | - Follow the project coding guidelines. In case of doubt, please contact the maintainers. 17 | - All your code will be released under the project license (see the [LICENSE](LICENSE) file for details), so make sure you and your collaborators (or employers) have no problems with it. -------------------------------------------------------------------------------- /src/robot_controllers/utils/math.hpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #ifndef ROBOT_CONTROLLERS_UTILS_MATH_HPP 22 | #define ROBOT_CONTROLLERS_UTILS_MATH_HPP 23 | 24 | #include 25 | 26 | namespace robot_controllers { 27 | namespace utils { 28 | Eigen::Vector3d rotation_error(const Eigen::Matrix3d& R_desired, const Eigen::Matrix3d& R_current); 29 | } // namespace utils 30 | } // namespace robot_controllers 31 | 32 | #endif -------------------------------------------------------------------------------- /src/examples/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #| 2 | #| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | #| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | #| Bernardo Fichera 5 | #| email: costashatz@gmail.com 6 | #| bernardo.fichera@epfl.ch 7 | #| website: lasa.epfl.ch 8 | #| 9 | #| This file is part of robot_controllers. 10 | #| 11 | #| robot_controllers is free software: you can redistribute it and/or modify 12 | #| it under the terms of the GNU General Public License as published by 13 | #| the Free Software Foundation, either version 3 of the License, or 14 | #| (at your option) any later version. 15 | #| 16 | #| robot_controllers is distributed in the hope that it will be useful, 17 | #| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | #| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | #| GNU General Public License for more details. 20 | #| 21 | add_executable(linear_test linear_test.cpp) 22 | 23 | # Require C++11 24 | set_property(TARGET linear_test PROPERTY CXX_STANDARD 11) 25 | set_property(TARGET linear_test PROPERTY CXX_STANDARD_REQUIRED ON) 26 | 27 | # add_library(PassiveDS SHARED IMPORTED) 28 | # set_property(TARGET PassiveDS PROPERTY IMPORTED_LOCATION ${CMAKE_CURRENT_BINARY_DIR}/../robot_controllers/low/PassiveDSController.so) 29 | 30 | # Add SIMD 31 | add_simd(linear_test) 32 | 33 | target_link_libraries(linear_test 34 | RobotControllers 35 | # PassiveDSController 36 | ) -------------------------------------------------------------------------------- /src/robot_controllers/utils/math.cpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #include "math.hpp" 22 | 23 | #include 24 | #include 25 | 26 | #include 27 | 28 | namespace robot_controllers { 29 | namespace utils { 30 | Eigen::Vector3d rotation_error(const Eigen::Matrix3d& R_desired, const Eigen::Matrix3d& R_current) 31 | { 32 | Eigen::AngleAxisd aa = Eigen::AngleAxisd(R_desired * R_current.transpose()); 33 | return aa.axis() * aa.angle(); 34 | } 35 | } // namespace utils 36 | } // namespace robot_controllers 37 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Robot Controllers 2 | This repo contains "low" and "high" level controllers for robot control 3 | 4 | ### Authors/Maintainers 5 | 6 | - Bernardo Fichera (bernardo.fichera@epfl.ch) 7 | - Konstantinos Chatzilygeroudis (costashatz@gmail.com) 8 | 9 | ### Available Controllers 10 | 11 | #### Low-Level controllers 12 | - Passive DS Controller: 13 | "Passive Interaction Control With Dynamical Systems", *Klas Kronander and Aude Billard*, 2016, https://ieeexplore.ieee.org/document/7358081 14 | - PID Controller 15 | 16 | #### High-Level controllers 17 | - Simple Linear DS high level controller 18 | - Force Modulation DS: "A Dynamical System Approach to Motion and Force Generation in Contact Tasks", *Amanhoud Walid, Mahdi Khoramshahi and Aude Billard*, 2019, http://lasa.epfl.ch/publications/uploadedFiles/RSS%20legacy%20paper_template%20LaTeX_compressed.pdf 19 | 20 | ### Installing 21 | 22 | #### Dependencies 23 | 24 | ```sh 25 | cd /source/directory 26 | git clone https://github.com/mosra/corrade.git 27 | cd corrade 28 | mkdir build && cd build 29 | cmake .. 30 | make -j 31 | sudo make install 32 | ``` 33 | 34 | #### Compilation 35 | 36 | ```sh 37 | mkdir build && cd build 38 | cmake -DCMAKE_INSTALL_PREFIX=/path/to/install/dir/ .. 39 | make && [sudo] make install (you might need sudo depending on your installation directory) 40 | ``` 41 | 42 | ### Contributing 43 | 44 | **robot_controllers** is being actively developed and the API is not stable. Please see [CONTRIBUTING](CONTRIBUTING.md) for more on how to help. 45 | 46 | ### Documentation 47 | 48 | UNDER CONSTRUCTION 49 | -------------------------------------------------------------------------------- /src/robot_controllers/high/ForceModDS.cpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #include 22 | 23 | #include "robot_controllers/high/ForceModDS.hpp" 24 | 25 | namespace robot_controllers { 26 | namespace high { 27 | bool ForceModDS::Init() 28 | { 29 | assert(params_.input_dim_ == params_.output_dim_); 30 | assert(params_.values_.size() > 0); 31 | 32 | SetDamping(params_.values_[0]); 33 | 34 | return true; 35 | } 36 | 37 | void ForceModDS::Update(const RobotState&) 38 | { 39 | output_.desired_.velocity_ = input_.desired_.force_ / damping_; 40 | } 41 | 42 | void ForceModDS::SetDamping(double damping) 43 | { 44 | damping_ = damping; 45 | assert(damping_ > 0.); 46 | } 47 | } // namespace high 48 | } // namespace robot_controllers 49 | 50 | CORRADE_PLUGIN_REGISTER(ForceModDSController, robot_controllers::high::ForceModDS, "RobotControllers.AbstractController/1.0") 51 | -------------------------------------------------------------------------------- /src/robot_controllers/high/ForceModDS.hpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #ifndef ROBOT_CONTROLLERS_HIGH_FORCE_MOD_DS_HPP 22 | #define ROBOT_CONTROLLERS_HIGH_FORCE_MOD_DS_HPP 23 | 24 | #include 25 | #include 26 | 27 | namespace robot_controllers { 28 | namespace high { 29 | class ForceModDS : public AbstractController { 30 | public: 31 | explicit ForceModDS(Corrade::PluginManager::AbstractManager& manager, const std::string& plugin) : AbstractController(manager, plugin) 32 | { 33 | input_ = RobotIO(IOType::Force); 34 | output_ = RobotIO(IOType::Velocity); 35 | } 36 | 37 | ForceModDS() : AbstractController(IOType::Force, IOType::Velocity) {} 38 | ~ForceModDS() {} 39 | 40 | bool Init() override; 41 | 42 | void SetIOTypes(IOTypes input_type, IOTypes output_type) override {} // Do not allow changes in the IO types 43 | 44 | void Update(const RobotState&) override; 45 | 46 | void SetDamping(double damping); 47 | 48 | protected: 49 | double damping_; 50 | }; 51 | } // namespace high 52 | } // namespace robot_controllers 53 | 54 | #endif -------------------------------------------------------------------------------- /src/robot_controllers/AbstractController.cpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #include "AbstractController.hpp" 22 | #include "robot_controllers/Config.hpp" 23 | 24 | namespace robot_controllers { 25 | void AbstractController::SetInput(const RobotState& input) { input_.desired_ = input; } 26 | 27 | void AbstractController::SetIOTypes(IOTypes input_type, IOTypes output_type) 28 | { 29 | // back-up old data 30 | RobotIO old_input = input_; 31 | RobotIO old_output = output_; 32 | 33 | // set new types 34 | input_ = RobotIO(input_type); 35 | input_.desired_ = old_input.desired_; 36 | 37 | output_ = RobotIO(output_type); 38 | output_.desired_ = old_output.desired_; 39 | } 40 | 41 | RobotIO AbstractController::GetInput() { return input_; } 42 | RobotIO AbstractController::GetOutput() { return output_; } 43 | 44 | void AbstractController::SetParams(const RobotParams& params) { params_ = params; } 45 | RobotParams AbstractController::GetParams() { return params_; } 46 | 47 | std::string AbstractController::pluginInterface() 48 | { 49 | return "RobotControllers.AbstractController/1.0"; 50 | } 51 | 52 | std::vector AbstractController::pluginSearchPaths() 53 | { 54 | return {std::string(ROBOT_CONTROLLERS_PLUGINS_DIR)}; 55 | } 56 | } // namespace robot_controllers -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #| 2 | #| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | #| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | #| Bernardo Fichera 5 | #| email: costashatz@gmail.com 6 | #| bernardo.fichera@epfl.ch 7 | #| website: lasa.epfl.ch 8 | #| 9 | #| This file is part of robot_controllers. 10 | #| 11 | #| robot_controllers is free software: you can redistribute it and/or modify 12 | #| it under the terms of the GNU General Public License as published by 13 | #| the Free Software Foundation, either version 3 of the License, or 14 | #| (at your option) any later version. 15 | #| 16 | #| robot_controllers is distributed in the hope that it will be useful, 17 | #| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | #| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | #| GNU General Public License for more details. 20 | #| 21 | cmake_minimum_required(VERSION 3.0) 22 | 23 | cmake_policy(SET CMP0057 NEW) 24 | 25 | # Set the name of your project here 26 | project(robot_controllers) 27 | 28 | # When enabling SIMD, both the dependencies (e.g. RBDyn) and subsequent code need to be compiled with SIMD 29 | option(ENABLE_SIMD "Build with all SIMD instructions on the current local machine" OFF) 30 | 31 | find_package(PkgConfig) 32 | 33 | # Find RBDyn library and dependencies 34 | pkg_search_module(Eigen3 REQUIRED eigen3) 35 | 36 | # Find Corrade 37 | find_package(Corrade REQUIRED Utility PluginManager) 38 | 39 | set(ROBOT_CONTROLLERS_BINARY_INSTALL_DIR bin) 40 | set(ROBOT_CONTROLLERS_LIBRARY_INSTALL_DIR lib${LIB_SUFFIX}) 41 | set(ROBOT_CONTROLLERS_INCLUDE_INSTALL_DIR include/robot_controllers) 42 | 43 | function(add_simd TARGET) 44 | if(ENABLE_SIMD) 45 | if(CMAKE_COMPILER_IS_GNUCXX) 46 | execute_process( 47 | COMMAND ${CMAKE_CXX_COMPILER} -dumpfullversion -dumpversion OUTPUT_VARIABLE GCC_VERSION) 48 | set(CXX_COMPILER_VERSION ${GCC_VERSION}) 49 | target_compile_options(${TARGET} PUBLIC -march=native) 50 | if(GCC_VERSION VERSION_GREATER 7.0) 51 | target_compile_options(${TARGET} PUBLIC -faligned-new) 52 | endif() 53 | elseif("${CMAKE_CXX_COMPILER_ID}" MATCHES "Clang") 54 | target_compile_options(${TARGET} PUBLIC -march=native -faligned-new) 55 | endif() 56 | endif() 57 | endfunction() 58 | 59 | add_subdirectory(src) 60 | -------------------------------------------------------------------------------- /src/robot_controllers/SumController.hpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #ifndef ROBOT_CONTROLLERS_SUM_CONTROLLER_HPP 22 | #define ROBOT_CONTROLLERS_SUM_CONTROLLER_HPP 23 | 24 | #include 25 | 26 | #include 27 | #include 28 | 29 | #include 30 | 31 | namespace robot_controllers { 32 | class SumController : public AbstractController { 33 | public: 34 | explicit SumController(Corrade::PluginManager::AbstractManager& manager, const std::string& plugin) : AbstractController(manager, plugin) {} 35 | SumController() : AbstractController() {} 36 | ~SumController() {} 37 | 38 | bool Init() override; 39 | void Update(const RobotState& state) override; 40 | 41 | void AddController(std::unique_ptr controller); 42 | 43 | template 44 | void AddController(Args... args) 45 | { 46 | auto ctrl_ptr = std::unique_ptr(new T(std::forward(args)...)); 47 | controllers_.emplace_back(std::move(ctrl_ptr)); 48 | } 49 | 50 | AbstractController* GetController(unsigned int index); 51 | const AbstractController* GetController(unsigned int index) const; 52 | 53 | unsigned int NumControllers() const { return controllers_.size(); } 54 | 55 | protected: 56 | std::vector> controllers_; 57 | 58 | bool CheckConsistency(); 59 | }; 60 | 61 | } // namespace robot_controllers 62 | 63 | #endif -------------------------------------------------------------------------------- /src/robot_controllers/high/LinearDS.hpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #ifndef ROBOT_CONTROLLERS_HIGH_LINEAR_DS_HPP 22 | #define ROBOT_CONTROLLERS_HIGH_LINEAR_DS_HPP 23 | 24 | #include 25 | 26 | #include 27 | 28 | namespace robot_controllers { 29 | namespace high { 30 | struct ParamsLinearDS { 31 | Eigen::MatrixXd A_; 32 | double time_step_; 33 | 34 | RobotParams ToRobotParams() const; 35 | void FromRobotParams(const RobotParams& p); 36 | }; 37 | 38 | class LinearDS : public AbstractController { 39 | public: 40 | explicit LinearDS(Corrade::PluginManager::AbstractManager& manager, const std::string& plugin) : AbstractController(manager, plugin) 41 | { 42 | input_ = RobotIO(IOType::Position); 43 | output_ = RobotIO(IOType::Velocity | IOType::Position); 44 | } 45 | 46 | LinearDS() : AbstractController(IOType::Position, IOType::Velocity | IOType::Position) {} 47 | ~LinearDS() {} 48 | 49 | bool Init() override; 50 | 51 | void SetIOTypes(IOTypes input_type, IOTypes output_type) override {} // Do not allow changes in the IO types 52 | 53 | void Update(const RobotState& state) override; 54 | 55 | void SetParams(const ParamsLinearDS& params); 56 | 57 | protected: 58 | ParamsLinearDS linear_ds_params_; 59 | }; 60 | } // namespace high 61 | } // namespace robot_controllers 62 | 63 | #endif -------------------------------------------------------------------------------- /src/robot_controllers/CascadeController.hpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #ifndef ROBOT_CONTROLLERS_CASCADE_CONTROLLER_HPP 22 | #define ROBOT_CONTROLLERS_CASCADE_CONTROLLER_HPP 23 | 24 | #include 25 | 26 | #include 27 | #include 28 | 29 | #include 30 | 31 | namespace robot_controllers { 32 | class CascadeController : public AbstractController { 33 | public: 34 | explicit CascadeController(Corrade::PluginManager::AbstractManager& manager, const std::string& plugin) : AbstractController(manager, plugin) {} 35 | 36 | CascadeController() : AbstractController() {} 37 | ~CascadeController() {} 38 | 39 | bool Init() override; 40 | void Update(const RobotState& state) override; 41 | 42 | void AddController(std::unique_ptr controller); 43 | 44 | template 45 | void AddController(Args... args) 46 | { 47 | auto ctrl_ptr = std::unique_ptr(new T(std::forward(args)...)); 48 | controllers_.emplace_back(std::move(ctrl_ptr)); 49 | } 50 | 51 | AbstractController* GetController(unsigned int index); 52 | const AbstractController* GetController(unsigned int index) const; 53 | 54 | unsigned int NumControllers() const { return controllers_.size(); } 55 | 56 | protected: 57 | std::vector> controllers_; 58 | 59 | bool CheckConsistency(); 60 | }; 61 | 62 | } // namespace robot_controllers 63 | 64 | #endif -------------------------------------------------------------------------------- /src/robot_controllers/low/Pid.hpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #ifndef ROBOT_CONTROLLERS_LOW_PID_HPP 22 | #define ROBOT_CONTROLLERS_LOW_PID_HPP 23 | 24 | #include 25 | #include 26 | 27 | namespace robot_controllers { 28 | namespace low { 29 | struct ParamsPid { 30 | Eigen::MatrixXd p_matrix_, 31 | d_matrix_, 32 | i_matrix_; 33 | double time_step_; 34 | 35 | RobotParams ToRobotParams() const; 36 | void FromRobotParams(const RobotParams& p); 37 | }; 38 | 39 | class Pid : public AbstractController { 40 | public: 41 | explicit Pid(Corrade::PluginManager::AbstractManager& manager, const std::string& plugin) : AbstractController(manager, plugin) 42 | { 43 | input_ = RobotIO(IOType::Position | IOType::Velocity); 44 | output_ = RobotIO(IOType::Force); 45 | } 46 | 47 | Pid(const unsigned int input_dim, const unsigned int output_dim, const double time_step) : AbstractController(IOType::Position | IOType::Velocity, IOType::Force) 48 | { 49 | params_.input_dim_ = input_dim; 50 | params_.output_dim_ = output_dim; 51 | params_.time_step_ = time_step; 52 | } 53 | 54 | ~Pid() {} 55 | 56 | bool Init() override; 57 | 58 | void Update(const RobotState& state) override; 59 | 60 | void SetParams(const ParamsPid& params); 61 | 62 | protected: 63 | ParamsPid pid_params_; 64 | Eigen::VectorXd intergral_error_; 65 | bool has_orientation_, has_position_, has_angular_velocity_, has_velocity_; 66 | unsigned int dim_; 67 | }; 68 | 69 | } // namespace low 70 | 71 | } // namespace robot_controllers 72 | 73 | #endif // ROBOT_CONTROLLERS_LOW_PID_HPP -------------------------------------------------------------------------------- /src/robot_controllers/low/PassiveDS.hpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #ifndef ROBOT_CONTROLLERS_LOW_PASSIVE_DS_HPP 22 | #define ROBOT_CONTROLLERS_LOW_PASSIVE_DS_HPP 23 | 24 | #include 25 | #include 26 | 27 | namespace robot_controllers { 28 | namespace low { 29 | class PassiveDS : public AbstractController { 30 | public: 31 | explicit PassiveDS(Corrade::PluginManager::AbstractManager& manager, const std::string& plugin) : AbstractController(manager, plugin) 32 | { 33 | input_ = RobotIO(IOType::Velocity); 34 | output_ = RobotIO(IOType::Force); 35 | } 36 | 37 | PassiveDS() : AbstractController(IOType::Velocity, IOType::Force) {} 38 | ~PassiveDS() {} 39 | 40 | bool Init() override; 41 | 42 | void SetIOTypes(IOTypes input_type, IOTypes output_type) override {} // Do not allow changes in the IO types 43 | 44 | void Update(const RobotState& state) override; 45 | 46 | void SetParams(unsigned int dim, const std::vector& eigvals); 47 | 48 | // SetInput -> Inherited from AbstractController 49 | // GetInput -> Inherited from AbstractController 50 | // GetOutput -> Inherited from AbstractController 51 | 52 | protected: 53 | Eigen::MatrixXd damping_matrix_, 54 | basis_matrix_, 55 | eig_matrix_; 56 | 57 | void Orthonormalize(); 58 | 59 | void AssertOrthonormalize(); 60 | 61 | void ComputeOrthonormalBasis(); 62 | 63 | void ComputeDamping(); 64 | 65 | // Missing function for set damping eigenvalue 66 | 67 | static constexpr double MINSPEED = 1e-6; 68 | static constexpr double FLOATEQUAL = 1e-6; 69 | }; 70 | } // namespace low 71 | } // namespace robot_controllers 72 | 73 | #endif -------------------------------------------------------------------------------- /src/robot_controllers/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #| 2 | #| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | #| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | #| Bernardo Fichera 5 | #| email: costashatz@gmail.com 6 | #| bernardo.fichera@epfl.ch 7 | #| website: lasa.epfl.ch 8 | #| 9 | #| This file is part of robot_controllers. 10 | #| 11 | #| robot_controllers is free software: you can redistribute it and/or modify 12 | #| it under the terms of the GNU General Public License as published by 13 | #| the Free Software Foundation, either version 3 of the License, or 14 | #| (at your option) any later version. 15 | #| 16 | #| robot_controllers is distributed in the hope that it will be useful, 17 | #| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | #| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | #| GNU General Public License for more details. 20 | #| 21 | set(robot_controllers_HEADERS 22 | AbstractController.hpp 23 | CascadeController.hpp 24 | SumController.hpp 25 | ${CMAKE_CURRENT_BINARY_DIR}/Config.hpp 26 | ) 27 | 28 | set(robot_controllers_SOURCES 29 | AbstractController.cpp 30 | CascadeController.cpp 31 | SumController.cpp 32 | ) 33 | 34 | set(robot_controllers_utils_HEADERS 35 | ${CMAKE_CURRENT_SOURCE_DIR}/utils/math.hpp 36 | ) 37 | 38 | set(robot_controllers_utils_SOURCES 39 | ${CMAKE_CURRENT_SOURCE_DIR}/utils/math.cpp 40 | ) 41 | 42 | set(ROBOT_CONTROLLERS_PLUGINS_DIR ${CMAKE_INSTALL_PREFIX}/lib/RobotControllersPlugins) 43 | 44 | configure_file(${CMAKE_CURRENT_SOURCE_DIR}/configure.h.cmake 45 | ${CMAKE_CURRENT_BINARY_DIR}/Config.hpp) 46 | 47 | add_library(RobotControllers SHARED ${robot_controllers_SOURCES} ${robot_controllers_utils_SOURCES}) 48 | 49 | target_include_directories(RobotControllers PUBLIC 50 | ${PROJECT_SOURCE_DIR}/src 51 | ${Eigen3_INCLUDE_DIRS} 52 | $ 53 | PRIVATE 54 | ${CMAKE_CURRENT_BINARY_DIR}/..) 55 | 56 | target_link_libraries(RobotControllers PUBLIC Corrade::PluginManager) 57 | 58 | # Require C++11 59 | set_property(TARGET RobotControllers PROPERTY CXX_STANDARD 11) 60 | set_property(TARGET RobotControllers PROPERTY CXX_STANDARD_REQUIRED ON) 61 | 62 | # Add SIMD 63 | add_simd(RobotControllers) 64 | 65 | install(TARGETS RobotControllers 66 | RUNTIME DESTINATION ${ROBOT_CONTROLLERS_BINARY_INSTALL_DIR} 67 | LIBRARY DESTINATION ${ROBOT_CONTROLLERS_LIBRARY_INSTALL_DIR} 68 | ARCHIVE DESTINATION ${ROBOT_CONTROLLERS_LIBRARY_INSTALL_DIR}) 69 | 70 | install(FILES ${robot_controllers_HEADERS} DESTINATION ${ROBOT_CONTROLLERS_INCLUDE_INSTALL_DIR}) 71 | install(FILES ${robot_controllers_utils_HEADERS} DESTINATION ${ROBOT_CONTROLLERS_INCLUDE_INSTALL_DIR}/utils) 72 | 73 | add_subdirectory(low) 74 | add_subdirectory(high) 75 | -------------------------------------------------------------------------------- /src/robot_controllers/high/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #| 2 | #| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | #| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | #| Bernardo Fichera 5 | #| email: costashatz@gmail.com 6 | #| bernardo.fichera@epfl.ch 7 | #| website: lasa.epfl.ch 8 | #| 9 | #| This file is part of robot_controllers. 10 | #| 11 | #| robot_controllers is free software: you can redistribute it and/or modify 12 | #| it under the terms of the GNU General Public License as published by 13 | #| the Free Software Foundation, either version 3 of the License, or 14 | #| (at your option) any later version. 15 | #| 16 | #| robot_controllers is distributed in the hope that it will be useful, 17 | #| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | #| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | #| GNU General Public License for more details. 20 | #| 21 | # All headers for installation 22 | set(high_level_controllers_HEADERS 23 | LinearDS.hpp 24 | ForceModDS.hpp 25 | ) 26 | 27 | # Linear DS plugin 28 | corrade_add_plugin(LinearDSController ${CMAKE_CURRENT_BINARY_DIR} "" Dummy.conf LinearDS.cpp ${robot_controllers_utils_SOURCES}) 29 | corrade_add_plugin(ForceModDSController ${CMAKE_CURRENT_BINARY_DIR} "" Dummy.conf ForceModDS.cpp ${robot_controllers_utils_SOURCES}) 30 | 31 | # Includes 32 | target_include_directories(LinearDSController PUBLIC 33 | ${PROJECT_SOURCE_DIR}/src 34 | ${Eigen3_INCLUDE_DIRS} 35 | $) 36 | 37 | target_include_directories(ForceModDSController PUBLIC 38 | ${PROJECT_SOURCE_DIR}/src 39 | ${Eigen3_INCLUDE_DIRS} 40 | $) 41 | 42 | # Require C++11 43 | set_property(TARGET LinearDSController PROPERTY CXX_STANDARD 11) 44 | set_property(TARGET LinearDSController PROPERTY CXX_STANDARD_REQUIRED ON) 45 | 46 | set_property(TARGET ForceModDSController PROPERTY CXX_STANDARD 11) 47 | set_property(TARGET ForceModDSController PROPERTY CXX_STANDARD_REQUIRED ON) 48 | 49 | target_link_libraries(LinearDSController PUBLIC RobotControllers) 50 | 51 | target_link_libraries(ForceModDSController PUBLIC RobotControllers) 52 | 53 | # Add SIMD 54 | add_simd(LinearDSController) 55 | add_simd(ForceModDSController) 56 | 57 | install(TARGETS LinearDSController 58 | LIBRARY DESTINATION ${ROBOT_CONTROLLERS_PLUGINS_DIR}) 59 | install(TARGETS ForceModDSController 60 | LIBRARY DESTINATION ${ROBOT_CONTROLLERS_PLUGINS_DIR}) 61 | 62 | install(FILES ${high_level_controllers_HEADERS} DESTINATION ${ROBOT_CONTROLLERS_INCLUDE_INSTALL_DIR}/high) 63 | install(FILES Dummy.conf DESTINATION ${ROBOT_CONTROLLERS_PLUGINS_DIR} RENAME LinearDSController.conf) 64 | install(FILES Dummy.conf DESTINATION ${ROBOT_CONTROLLERS_PLUGINS_DIR} RENAME ForceModDSController.conf) -------------------------------------------------------------------------------- /src/robot_controllers/low/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #| 2 | #| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | #| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | #| Bernardo Fichera 5 | #| email: costashatz@gmail.com 6 | #| bernardo.fichera@epfl.ch 7 | #| website: lasa.epfl.ch 8 | #| 9 | #| This file is part of robot_controllers. 10 | #| 11 | #| robot_controllers is free software: you can redistribute it and/or modify 12 | #| it under the terms of the GNU General Public License as published by 13 | #| the Free Software Foundation, either version 3 of the License, or 14 | #| (at your option) any later version. 15 | #| 16 | #| robot_controllers is distributed in the hope that it will be useful, 17 | #| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | #| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | #| GNU General Public License for more details. 20 | #| 21 | # All headers for installation 22 | set(low_level_controllers_HEADERS 23 | PassiveDS.hpp 24 | Pid.hpp 25 | ) 26 | 27 | # PID plugin 28 | corrade_add_plugin(PidController ${CMAKE_CURRENT_BINARY_DIR} "" Dummy.conf Pid.cpp ${robot_controllers_utils_SOURCES}) 29 | 30 | # Includes 31 | target_include_directories(PidController PUBLIC 32 | ${PROJECT_SOURCE_DIR}/src 33 | ${Eigen3_INCLUDE_DIRS} 34 | $) 35 | 36 | # Require C++11 37 | set_property(TARGET PidController PROPERTY CXX_STANDARD 11) 38 | set_property(TARGET PidController PROPERTY CXX_STANDARD_REQUIRED ON) 39 | 40 | target_link_libraries(PidController PUBLIC RobotControllers) 41 | 42 | # Add SIMD 43 | add_simd(PidController) 44 | 45 | install(TARGETS PidController 46 | LIBRARY DESTINATION ${ROBOT_CONTROLLERS_PLUGINS_DIR}) 47 | 48 | # PassiveDS plugin 49 | corrade_add_plugin(PassiveDSController ${CMAKE_CURRENT_BINARY_DIR} "" Dummy.conf PassiveDS.cpp ${robot_controllers_utils_SOURCES}) 50 | 51 | # Includes 52 | target_include_directories(PassiveDSController PUBLIC 53 | ${PROJECT_SOURCE_DIR}/src 54 | ${Eigen3_INCLUDE_DIRS} 55 | $) 56 | 57 | # Require C++11 58 | set_property(TARGET PassiveDSController PROPERTY CXX_STANDARD 11) 59 | set_property(TARGET PassiveDSController PROPERTY CXX_STANDARD_REQUIRED ON) 60 | 61 | target_link_libraries(PassiveDSController PUBLIC RobotControllers) 62 | 63 | # Add SIMD 64 | add_simd(PassiveDSController) 65 | 66 | install(TARGETS PassiveDSController 67 | LIBRARY DESTINATION ${ROBOT_CONTROLLERS_PLUGINS_DIR}) 68 | 69 | install(FILES ${low_level_controllers_HEADERS} DESTINATION ${ROBOT_CONTROLLERS_INCLUDE_INSTALL_DIR}/low) 70 | install(FILES Dummy.conf DESTINATION ${ROBOT_CONTROLLERS_PLUGINS_DIR} RENAME PidController.conf) 71 | install(FILES Dummy.conf DESTINATION ${ROBOT_CONTROLLERS_PLUGINS_DIR} RENAME PassiveDSController.conf) -------------------------------------------------------------------------------- /src/robot_controllers/CascadeController.cpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #include 22 | 23 | namespace robot_controllers { 24 | bool CascadeController::Init() 25 | { 26 | for (auto& ctrl : controllers_) 27 | if (!ctrl->Init()) 28 | return false; 29 | 30 | return CheckConsistency(); 31 | } 32 | 33 | void CascadeController::Update(const RobotState& state) 34 | { 35 | RobotState curr = input_.desired_; 36 | for (auto& ctrl : controllers_) { 37 | ctrl->SetInput(curr); 38 | ctrl->Update(state); 39 | curr = ctrl->GetOutput().desired_; 40 | } 41 | output_.desired_ = curr; 42 | } 43 | 44 | void CascadeController::AddController(std::unique_ptr controller) 45 | { 46 | controllers_.emplace_back(std::move(controller)); 47 | } 48 | 49 | AbstractController* CascadeController::GetController(unsigned int index) 50 | { 51 | assert(index < controllers_.size()); 52 | return controllers_[index].get(); 53 | } 54 | 55 | const AbstractController* CascadeController::GetController(unsigned int index) const 56 | { 57 | assert(index < controllers_.size()); 58 | return controllers_[index].get(); 59 | } 60 | 61 | bool CascadeController::CheckConsistency() 62 | { 63 | if (controllers_.size() == 0) 64 | return false; 65 | input_ = RobotIO(controllers_.front()->GetInput().GetType()); 66 | output_ = RobotIO(controllers_.back()->GetOutput().GetType()); 67 | 68 | IOTypes t = IOType::All; 69 | for (auto& ctrl : controllers_) { 70 | if (!(ctrl->GetInput().GetType() & t)) 71 | return false; 72 | t = ctrl->GetOutput().GetType(); 73 | } 74 | 75 | if (controllers_.back()->GetOutput().GetType() & output_.GetType()) 76 | return true; 77 | 78 | return false; 79 | } 80 | } // namespace robot_controllers 81 | 82 | CORRADE_PLUGIN_REGISTER(CascadeController, robot_controllers::CascadeController, "RobotControllers.AbstractController/1.0") -------------------------------------------------------------------------------- /src/examples/linear_test.cpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #include 22 | #include 23 | 24 | #include 25 | #include 26 | #include 27 | #include 28 | #include 29 | 30 | int main(int argc, char const* argv[]) 31 | { 32 | Corrade::PluginManager::Manager manager; 33 | 34 | if (!(manager.load("PassiveDSController") & Corrade::PluginManager::LoadState::Loaded)) { 35 | std::cout << "BA" << std::endl; 36 | } 37 | 38 | Corrade::Containers::Pointer ctrl = manager.instantiate("PassiveDSController"); 39 | auto c = static_cast(ctrl.get()); 40 | // c->SetParams(5, {1., 2.}); 41 | // robot_controllers::low::PassiveDS pds; 42 | // pds.SetParams(5, {1., 2.}); 43 | 44 | // Eigen::MatrixXd A = Eigen::MatrixXd::Identity(5, 5); 45 | // robot_controllers::high::LinearDS lds(A); 46 | 47 | // robot_controllers::CascadeController cascade(robot_controllers::IOType::Position, robot_controllers::IOType::Force); 48 | // cascade.AddController(A); 49 | // cascade.AddController(5, 1., 2.); 50 | 51 | // std::cout << cascade.Init() << std::endl; 52 | 53 | // robot_controllers::RobotState desired; 54 | // desired.position_ = Eigen::VectorXd::Zero(5); 55 | // cascade.SetInput(desired); 56 | 57 | // robot_controllers::RobotState st; 58 | // st.position_ = Eigen::VectorXd::Ones(5).array() * 0.1; 59 | // st.velocity_ = Eigen::VectorXd::Zero(5); 60 | // cascade.Update(st); 61 | 62 | // std::cout << cascade.GetOutput().desired_.force_.transpose() << std::endl; 63 | 64 | // robot_controllers::SumController sum(robot_controllers::IOType::Velocity, robot_controllers::IOType::Force); 65 | // sum.AddController(5, 1., 2.); 66 | // sum.AddController(5, 4., 4.); 67 | 68 | // desired.velocity_ = Eigen::VectorXd::Ones(5); 69 | // sum.SetInput(desired); 70 | 71 | // sum.Update(st); 72 | 73 | // std::cout << sum.GetOutput().desired_.force_.transpose() << std::endl; 74 | 75 | return 0; 76 | } 77 | -------------------------------------------------------------------------------- /src/robot_controllers/high/LinearDS.cpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #include 22 | 23 | #include "robot_controllers/high/LinearDS.hpp" 24 | 25 | namespace robot_controllers { 26 | namespace high { 27 | RobotParams ParamsLinearDS::ToRobotParams() const 28 | { 29 | RobotParams p; 30 | 31 | p.input_dim_ = A_.rows(); 32 | p.output_dim_ = A_.cols(); 33 | p.time_step_ = time_step_; 34 | 35 | unsigned int size = A_.size(); 36 | 37 | if (size > 0) { 38 | p.values_.resize(size); 39 | 40 | Eigen::MatrixXd::Map(p.values_.data(), p.output_dim_, p.input_dim_) = A_; 41 | } 42 | 43 | return p; 44 | } 45 | 46 | void ParamsLinearDS::FromRobotParams(const RobotParams& p) 47 | { 48 | if (p.input_dim_ == 0 || p.output_dim_ == 0) 49 | return; 50 | 51 | time_step_ = p.time_step_; 52 | 53 | A_ = Eigen::MatrixXd::Zero(p.output_dim_, p.input_dim_); 54 | 55 | unsigned int size = p.values_.size(); 56 | // if only one element 57 | if (size == 1) { 58 | A_.diagonal() = Eigen::VectorXd::Constant(p.output_dim_, p.values_[0]); 59 | } 60 | else if (size == p.input_dim_) { // diagonal elements 61 | A_.diagonal() = Eigen::VectorXd::Map(p.values_.data(), p.output_dim_); 62 | } 63 | else { // full matrix 64 | A_ = Eigen::MatrixXd::Map(p.values_.data(), p.output_dim_, p.input_dim_); 65 | } 66 | } 67 | 68 | bool LinearDS::Init() 69 | { 70 | linear_ds_params_.FromRobotParams(params_); 71 | 72 | input_.desired_.position_ = Eigen::VectorXd::Zero(params_.input_dim_); 73 | return true; 74 | } 75 | 76 | void LinearDS::Update(const RobotState& state) 77 | { 78 | output_.desired_.velocity_ = linear_ds_params_.A_ * (input_.desired_.position_ - state.position_); 79 | output_.desired_.position_ = state.position_ + params_.time_step_ * output_.desired_.velocity_; 80 | } 81 | 82 | void LinearDS::SetParams(const ParamsLinearDS& params) 83 | { 84 | linear_ds_params_ = params; 85 | params_ = linear_ds_params_.ToRobotParams(); 86 | } 87 | } // namespace high 88 | } // namespace robot_controllers 89 | 90 | CORRADE_PLUGIN_REGISTER(LinearDSController, robot_controllers::high::LinearDS, "RobotControllers.AbstractController/1.0") -------------------------------------------------------------------------------- /src/robot_controllers/SumController.cpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #include 22 | 23 | namespace robot_controllers { 24 | bool SumController::Init() 25 | { 26 | for (auto& ctrl : controllers_) 27 | if (!ctrl->Init()) 28 | return false; 29 | 30 | return CheckConsistency(); 31 | } 32 | 33 | void SumController::Update(const RobotState& state) 34 | { 35 | RobotState result; 36 | #define add_result(name) \ 37 | { \ 38 | if (result.name.size() == 0) \ 39 | result.name = Eigen::VectorXd::Zero(out.name.size()); \ 40 | result.name += out.name; \ 41 | } 42 | 43 | for (unsigned int i = 0; i < controllers_.size(); i++) { 44 | auto& ctrl = controllers_[i]; 45 | ctrl->SetInput(input_.desired_); 46 | ctrl->Update(state); 47 | RobotState out = ctrl->GetOutput().desired_; 48 | 49 | IOTypes t = ctrl->GetOutput().GetType(); 50 | if (t & IOType::Position) 51 | add_result(position_); 52 | if (t & IOType::Orientation) 53 | add_result(orientation_); 54 | if (t & IOType::Velocity) 55 | add_result(velocity_); 56 | if (t & IOType::AngularVelocity) 57 | add_result(angular_velocity_); 58 | if (t & IOType::Acceleration) 59 | add_result(acceleration_); 60 | if (t & IOType::AngularAcceleration) 61 | add_result(angular_acceleration_); 62 | if (t & IOType::Force) 63 | add_result(force_); 64 | if (t & IOType::Torque) 65 | add_result(torque_); 66 | } 67 | #undef add_result 68 | output_.desired_ = result; 69 | } 70 | 71 | void SumController::AddController(std::unique_ptr controller) 72 | { 73 | controllers_.emplace_back(std::move(controller)); 74 | } 75 | 76 | AbstractController* SumController::GetController(unsigned int index) 77 | { 78 | assert(index < controllers_.size()); 79 | return controllers_[index].get(); 80 | } 81 | 82 | const AbstractController* SumController::GetController(unsigned int index) const 83 | { 84 | assert(index < controllers_.size()); 85 | return controllers_[index].get(); 86 | } 87 | 88 | bool SumController::CheckConsistency() 89 | { 90 | if (controllers_.size() == 0) 91 | return false; 92 | IOTypes in_type = controllers_.front()->GetInput().GetType(); 93 | IOTypes out_type = controllers_.back()->GetOutput().GetType(); 94 | 95 | for (auto& ctrl : controllers_) { 96 | in_type = in_type | ctrl->GetInput().GetType(); 97 | out_type = out_type | ctrl->GetOutput().GetType(); 98 | } 99 | 100 | input_ = RobotIO(in_type); 101 | output_ = RobotIO(out_type); 102 | 103 | return true; 104 | } 105 | } // namespace robot_controllers 106 | 107 | CORRADE_PLUGIN_REGISTER(SumController, robot_controllers::SumController, "RobotControllers.AbstractController/1.0") -------------------------------------------------------------------------------- /src/robot_controllers/AbstractController.hpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #ifndef ROBOT_CONTROLLERS_ABSTRACT_CONTROLLER_HPP 22 | #define ROBOT_CONTROLLERS_ABSTRACT_CONTROLLER_HPP 23 | 24 | #include 25 | 26 | #include 27 | #include 28 | 29 | #include 30 | #include 31 | 32 | namespace robot_controllers { 33 | enum class IOType : unsigned int { 34 | Position = 1 << 0, // Contains position information 35 | Orientation = 1 << 1, // Contains orientation information 36 | Velocity = 1 << 2, // Contains velocity information 37 | AngularVelocity = 1 << 3, // Contains angular velocity information 38 | Acceleration = 1 << 4, // Contains acceleration information 39 | AngularAcceleration = 1 << 5, // Contains angular acceleration information 40 | Force = 1 << 6, // Contains force information 41 | Torque = 1 << 7, // Contains torque information 42 | All = Position | Orientation | Velocity | AngularVelocity | Acceleration | AngularAcceleration | Force | Torque // Contains everything 43 | }; // enum class IOTypes 44 | 45 | using IOTypes = Corrade::Containers::EnumSet; 46 | CORRADE_ENUMSET_OPERATORS(IOTypes) 47 | 48 | struct RobotState { 49 | Eigen::VectorXd position_, 50 | velocity_, 51 | acceleration_, 52 | force_; 53 | Eigen::VectorXd orientation_, 54 | angular_velocity_, 55 | angular_acceleration_, 56 | torque_; 57 | }; 58 | 59 | struct RobotIO { 60 | public: 61 | RobotIO() {} 62 | RobotIO(IOTypes type) : type_(type) {} 63 | 64 | IOTypes GetType() const { return type_; } 65 | 66 | RobotState desired_; 67 | 68 | private: 69 | // this should never change 70 | IOTypes type_; 71 | }; // struct RobotIO 72 | 73 | struct RobotParams { 74 | unsigned int input_dim_, output_dim_; 75 | double time_step_; 76 | std::vector values_; 77 | }; 78 | 79 | class AbstractController : public Corrade::PluginManager::AbstractManagingPlugin { 80 | public: 81 | explicit AbstractController(Corrade::PluginManager::AbstractManager& manager, const std::string& plugin) : Corrade::PluginManager::AbstractManagingPlugin{manager, plugin} {} 82 | 83 | AbstractController() {} 84 | AbstractController(IOTypes input_type, IOTypes output_type) : input_(input_type), output_(output_type) {} 85 | virtual ~AbstractController() {} 86 | 87 | // Init should be called after SetParams 88 | virtual bool Init() = 0; 89 | virtual void Update(const RobotState&) = 0; 90 | 91 | void SetInput(const RobotState& input); 92 | virtual void SetIOTypes(IOTypes input_type, IOTypes output_type); 93 | RobotIO GetInput(); 94 | RobotIO GetOutput(); 95 | 96 | void SetParams(const RobotParams& params); 97 | RobotParams GetParams(); 98 | 99 | // Corrade Plugin Methods 100 | static std::string pluginInterface(); 101 | static std::vector pluginSearchPaths(); 102 | 103 | protected: 104 | RobotIO input_; 105 | RobotIO output_; 106 | RobotParams params_; 107 | }; // class AbstractController 108 | 109 | } // namespace robot_controllers 110 | 111 | #endif -------------------------------------------------------------------------------- /add_license.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | # encoding: utf-8 3 | #| 4 | #| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 5 | #| Authors: Konstantinos Chatzilygeroudis (maintainer) 6 | #| Bernardo Fichera 7 | #| email: costashatz@gmail.com 8 | #| bernardo.fichera@epfl.ch 9 | #| website: lasa.epfl.ch 10 | #| 11 | #| This file is part of robot_controllers. 12 | #| 13 | #| robot_controllers is free software: you can redistribute it and/or modify 14 | #| it under the terms of the GNU General Public License as published by 15 | #| the Free Software Foundation, either version 3 of the License, or 16 | #| (at your option) any later version. 17 | #| 18 | #| robot_controllers is distributed in the hope that it will be useful, 19 | #| but WITHOUT ANY WARRANTY; without even the implied warranty of 20 | #| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 21 | #| GNU General Public License for more details. 22 | #| 23 | import fnmatch,re 24 | import os, shutil, sys 25 | 26 | license = '''Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 27 | Authors: Konstantinos Chatzilygeroudis (maintainer) 28 | Bernardo Fichera 29 | email: costashatz@gmail.com 30 | bernardo.fichera@epfl.ch 31 | website: lasa.epfl.ch 32 | 33 | This file is part of robot_controllers. 34 | 35 | robot_controllers is free software: you can redistribute it and/or modify 36 | it under the terms of the GNU General Public License as published by 37 | the Free Software Foundation, either version 3 of the License, or 38 | (at your option) any later version. 39 | 40 | robot_controllers is distributed in the hope that it will be useful, 41 | but WITHOUT ANY WARRANTY; without even the implied warranty of 42 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 43 | GNU General Public License for more details. 44 | ''' 45 | 46 | def make_dirlist(folder, extensions): 47 | matches = [] 48 | for root, dirnames, filenames in os.walk(folder): 49 | for ext in extensions: 50 | for filename in fnmatch.filter(filenames, '*' + ext): 51 | matches.append(os.path.join(root, filename)) 52 | return matches 53 | 54 | def insert_header(fname, prefix, postfix, license, kept_header = []): 55 | input = open(fname, 'r') 56 | ofname = '/tmp/' + fname.split('/')[-1] 57 | output = open(ofname, 'w') 58 | for line in kept_header: 59 | output.write(line + '\n') 60 | output.write(prefix + '\n') 61 | has_postfix = len(postfix)>0 62 | my_prefix = prefix 63 | if has_postfix: 64 | my_prefix = '' 65 | for line in license.split('\n'): 66 | if len(line)>0: 67 | output.write(my_prefix + ' ' + line + '\n') 68 | else: 69 | output.write(my_prefix + '\n') 70 | if has_postfix: 71 | output.write(postfix + '\n') 72 | in_header = False 73 | for line in input: 74 | header = len(filter(lambda x: x == line[0:len(x)], kept_header)) != 0 75 | check_prefix = (line[0:len(prefix)] == prefix) 76 | check_postfix = (has_postfix and (line[0:len(postfix)] == postfix)) 77 | if check_prefix and has_postfix: 78 | in_header = True 79 | if check_postfix: 80 | in_header = False 81 | if (not in_header) and (not check_prefix) and (not header) and (not check_postfix): 82 | output.write(line) 83 | output.close() 84 | shutil.move(ofname, fname) 85 | 86 | def insert(directory): 87 | # cpp 88 | cpp = make_dirlist(directory, ['.hpp', '.cpp', '.h', '.c', '.cc']) 89 | for i in cpp: 90 | insert_header(i, '//|', '', license) 91 | # py 92 | py = make_dirlist(directory, ['.py']) 93 | for i in py: 94 | insert_header(i, '#|', '', license, ['#!/usr/bin/env python', '# encoding: utf-8']) 95 | # CMake 96 | cmake = make_dirlist(directory, ['CMakeLists.txt']) 97 | for i in cmake: 98 | # metapackages should not have any comments 99 | if i.endswith('iiwa_ros/CMakeLists.txt'): 100 | continue 101 | insert_header(i, '#|', '', license) 102 | # # XML/URDF 103 | xml_urdf = make_dirlist(directory, ['.xml', '.urdf', '.xacro', '.launch']) 104 | for i in xml_urdf: 105 | header = [''] 106 | insert_header(i, '', license, header) 107 | 108 | if __name__ == '__main__': 109 | insert('.') -------------------------------------------------------------------------------- /src/robot_controllers/low/PassiveDS.cpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #include 22 | 23 | #include "robot_controllers/low/PassiveDS.hpp" 24 | 25 | namespace robot_controllers { 26 | namespace low { 27 | bool PassiveDS::Init() 28 | { 29 | assert(params_.input_dim_ == params_.output_dim_); 30 | // Initialize the basis matrix 31 | basis_matrix_ = Eigen::MatrixXd::Random(params_.input_dim_, params_.output_dim_); 32 | Orthonormalize(); 33 | AssertOrthonormalize(); 34 | 35 | // Initialize the damping matrix 36 | damping_matrix_ = Eigen::MatrixXd::Zero(params_.input_dim_, params_.output_dim_); 37 | 38 | SetParams(params_.input_dim_, params_.values_); 39 | 40 | return true; 41 | } 42 | 43 | void PassiveDS::Update(const RobotState& state) 44 | { 45 | ComputeDamping(); 46 | output_.desired_.force_ = -damping_matrix_ * state.velocity_ + eig_matrix_(0, 0) * input_.desired_.velocity_; 47 | } 48 | 49 | void PassiveDS::SetParams(unsigned int dim, const std::vector& eigvals) 50 | { 51 | assert(eigvals.size() <= dim && eigvals.size() > 0); 52 | 53 | params_.input_dim_ = dim; 54 | params_.output_dim_ = dim; 55 | 56 | // Fill the eigenvalue matrix 57 | eig_matrix_ = Eigen::MatrixXd::Zero(dim, dim); 58 | 59 | for (size_t i = 0; i < eigvals.size(); i++) 60 | eig_matrix_(i, i) = eigvals[i]; 61 | 62 | for (size_t i = eigvals.size(); i < dim; i++) 63 | eig_matrix_(i, i) = eigvals.back(); 64 | } 65 | 66 | void PassiveDS::Orthonormalize() 67 | { 68 | assert(basis_matrix_.rows() == basis_matrix_.cols()); 69 | unsigned int dim = basis_matrix_.rows(); 70 | basis_matrix_.col(0).normalize(); 71 | for (unsigned int i = 1; i < dim; i++) { 72 | for (unsigned int j = 0; j < i; j++) 73 | basis_matrix_.col(i) -= basis_matrix_.col(j).dot(basis_matrix_.col(i)) * basis_matrix_.col(j); 74 | basis_matrix_.col(i).normalize(); 75 | } 76 | } 77 | 78 | void PassiveDS::AssertOrthonormalize() 79 | { 80 | uint dim = basis_matrix_.cols(); 81 | for (int i = 0; i < dim; ++i) { 82 | assert(abs(basis_matrix_.col(i).norm() - 1.0) < FLOATEQUAL); 83 | for (int j = 0; j < i; ++j) { 84 | assert(abs(basis_matrix_.col(i).dot(basis_matrix_.col(j))) < FLOATEQUAL); 85 | } 86 | } 87 | } 88 | 89 | void PassiveDS::ComputeOrthonormalBasis() 90 | { 91 | Eigen::VectorXd dir = input_.desired_.velocity_.normalized(); // or normalize 92 | assert(dir.rows() == basis_matrix_.rows()); 93 | basis_matrix_.col(0) = dir; 94 | Orthonormalize(); 95 | } 96 | 97 | void PassiveDS::ComputeDamping() 98 | { 99 | // only proceed of we have a minimum velocity norm! 100 | if (input_.desired_.velocity_.norm() > MINSPEED) 101 | ComputeOrthonormalBasis(); 102 | // otherwise just use the last computed basis 103 | damping_matrix_ = basis_matrix_ * eig_matrix_ * basis_matrix_.transpose(); 104 | } 105 | 106 | } // namespace low 107 | } // namespace robot_controllers 108 | 109 | CORRADE_PLUGIN_REGISTER(PassiveDSController, robot_controllers::low::PassiveDS, "RobotControllers.AbstractController/1.0") 110 | -------------------------------------------------------------------------------- /src/robot_controllers/low/Pid.cpp: -------------------------------------------------------------------------------- 1 | //| 2 | //| Copyright (C) 2019 Learning Algorithms and Systems Laboratory, EPFL, Switzerland 3 | //| Authors: Konstantinos Chatzilygeroudis (maintainer) 4 | //| Bernardo Fichera 5 | //| email: costashatz@gmail.com 6 | //| bernardo.fichera@epfl.ch 7 | //| website: lasa.epfl.ch 8 | //| 9 | //| This file is part of robot_controllers. 10 | //| 11 | //| robot_controllers is free software: you can redistribute it and/or modify 12 | //| it under the terms of the GNU General Public License as published by 13 | //| the Free Software Foundation, either version 3 of the License, or 14 | //| (at your option) any later version. 15 | //| 16 | //| robot_controllers is distributed in the hope that it will be useful, 17 | //| but WITHOUT ANY WARRANTY; without even the implied warranty of 18 | //| MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 19 | //| GNU General Public License for more details. 20 | //| 21 | #include "robot_controllers/low/Pid.hpp" 22 | #include "robot_controllers/utils/math.hpp" 23 | 24 | #include 25 | 26 | namespace robot_controllers { 27 | namespace low { 28 | RobotParams ParamsPid::ToRobotParams() const 29 | { 30 | assert(p_matrix_.size() == d_matrix_.size() && p_matrix_.size() == i_matrix_.size()); 31 | RobotParams p; 32 | 33 | p.input_dim_ = p_matrix_.rows(); 34 | p.output_dim_ = p_matrix_.cols(); 35 | p.time_step_ = time_step_; 36 | 37 | unsigned int size = p_matrix_.size() + d_matrix_.size() + i_matrix_.size(); 38 | 39 | if (size > 0) { 40 | p.values_.resize(size); 41 | 42 | Eigen::MatrixXd::Map(p.values_.data(), p.output_dim_, p.input_dim_) = p_matrix_; 43 | Eigen::MatrixXd::Map(p.values_.data() + p_matrix_.size(), p.output_dim_, p.input_dim_) = d_matrix_; 44 | Eigen::MatrixXd::Map(p.values_.data() + p_matrix_.size() + d_matrix_.size(), p.output_dim_, p.input_dim_) = i_matrix_; 45 | } 46 | 47 | return p; 48 | } 49 | 50 | void ParamsPid::FromRobotParams(const RobotParams& p) 51 | { 52 | if (p.input_dim_ == 0 || p.output_dim_ == 0 || p.values_.size() < 2) 53 | return; 54 | 55 | time_step_ = p.time_step_; 56 | 57 | p_matrix_.resize(p.output_dim_, p.input_dim_); 58 | d_matrix_.resize(p.output_dim_, p.input_dim_); 59 | i_matrix_.resize(p.output_dim_, p.input_dim_); 60 | 61 | unsigned int size = p.values_.size(); 62 | // <= 3 values: one for P, one for D, one for I (in that order) 63 | if (size <= 3) { 64 | p_matrix_ = Eigen::MatrixXd::Zero(p.output_dim_, p.input_dim_); 65 | d_matrix_ = Eigen::MatrixXd::Zero(p.output_dim_, p.input_dim_); 66 | i_matrix_ = Eigen::MatrixXd::Zero(p.output_dim_, p.input_dim_); 67 | 68 | p_matrix_.diagonal() = Eigen::VectorXd::Constant(p.output_dim_, p.values_[0]); 69 | d_matrix_.diagonal() = Eigen::VectorXd::Constant(p.output_dim_, p.values_[1]); 70 | if (size == 3) { 71 | i_matrix_.diagonal() = Eigen::VectorXd::Constant(p.output_dim_, p.values_[2]); 72 | } 73 | } 74 | // diagonal elements only: for P, for D and for I (in that order) 75 | else if (size <= 3 * p.output_dim_) { 76 | p_matrix_ = Eigen::MatrixXd::Zero(p.output_dim_, p.input_dim_); 77 | d_matrix_ = Eigen::MatrixXd::Zero(p.output_dim_, p.input_dim_); 78 | i_matrix_ = Eigen::MatrixXd::Zero(p.output_dim_, p.input_dim_); 79 | 80 | p_matrix_.diagonal() = Eigen::VectorXd::Map(p.values_.data(), p.output_dim_); 81 | d_matrix_.diagonal() = Eigen::VectorXd::Map(p.values_.data() + p.output_dim_, p.output_dim_); 82 | if (size == 3 * p.output_dim_) { 83 | i_matrix_.diagonal() = Eigen::VectorXd::Map(p.values_.data() + 2 * p.output_dim_, p.output_dim_); 84 | } 85 | } 86 | else { // full matrices 87 | p_matrix_ = Eigen::MatrixXd::Map(p.values_.data(), p.output_dim_, p.input_dim_); 88 | d_matrix_ = Eigen::MatrixXd::Map(p.values_.data() + p_matrix_.size(), p.output_dim_, p.input_dim_); 89 | i_matrix_ = Eigen::MatrixXd::Map(p.values_.data() + p_matrix_.size() + d_matrix_.size(), p.output_dim_, p.input_dim_); 90 | } 91 | } 92 | 93 | bool Pid::Init() 94 | { 95 | // sanity checks 96 | // if we have position input, output needs to have force 97 | if (((input_.GetType() & IOType::Position) || (input_.GetType() & IOType::Velocity)) && !(output_.GetType() & IOType::Force)) 98 | return false; 99 | // if we have orientation input, output needs to have torque 100 | if (((input_.GetType() & IOType::Orientation) || (input_.GetType() & IOType::AngularVelocity)) && !(output_.GetType() & IOType::Torque)) 101 | return false; 102 | 103 | pid_params_.FromRobotParams(params_); 104 | 105 | has_orientation_ = has_position_ = has_angular_velocity_ = has_velocity_ = false; 106 | 107 | if (input_.GetType() & IOType::Position) 108 | has_position_ = true; 109 | if (input_.GetType() & IOType::Velocity) 110 | has_velocity_ = true; 111 | if (input_.GetType() & IOType::Orientation) 112 | has_orientation_ = true; 113 | if (input_.GetType() & IOType::AngularVelocity) 114 | has_angular_velocity_ = true; 115 | 116 | dim_ = params_.input_dim_; 117 | 118 | if (has_orientation_ || has_angular_velocity_) { 119 | // Orientation is always 3D 120 | dim_ = params_.input_dim_ - 3; 121 | } 122 | 123 | if ((has_orientation_ || has_angular_velocity_) && (params_.input_dim_ < 3)) { 124 | // if we have orientation, then dimension of positions/orientations should be 3 125 | return false; 126 | } 127 | 128 | intergral_error_ = Eigen::VectorXd::Zero(params_.input_dim_); 129 | 130 | return true; 131 | } 132 | 133 | void Pid::Update(const RobotState& curr_state) 134 | { 135 | Eigen::VectorXd curr_pose = Eigen::VectorXd::Zero(params_.input_dim_); 136 | if (has_position_) 137 | curr_pose.tail(dim_) = curr_state.position_; 138 | if (has_orientation_) // Orientation goes first 139 | curr_pose.head(3) = curr_state.orientation_; 140 | 141 | Eigen::VectorXd desired_pose = Eigen::VectorXd::Zero(params_.input_dim_); 142 | if (has_position_) 143 | desired_pose.tail(dim_) = input_.desired_.position_; 144 | if (has_orientation_) 145 | desired_pose.head(3) = input_.desired_.orientation_; 146 | 147 | Eigen::VectorXd error = desired_pose - curr_pose; 148 | if (has_orientation_) { 149 | Eigen::Matrix3d curr_rot = Eigen::AngleAxisd(curr_state.orientation_.norm(), curr_state.orientation_.normalized()).toRotationMatrix(); 150 | Eigen::Matrix3d desired_rot = Eigen::AngleAxisd(input_.desired_.orientation_.norm(), input_.desired_.orientation_.normalized()).toRotationMatrix(); 151 | error.head(3) = utils::rotation_error(desired_rot, curr_rot); 152 | } 153 | 154 | Eigen::VectorXd vel_error = Eigen::VectorXd::Zero(params_.input_dim_); 155 | // if not velocity given, we assume target is zero velocities 156 | if (has_position_) 157 | vel_error.tail(dim_) = -curr_state.velocity_; 158 | if (has_velocity_) 159 | vel_error.tail(dim_) += input_.desired_.velocity_; 160 | 161 | if (has_orientation_) 162 | vel_error.head(3) = -curr_state.angular_velocity_; 163 | if (has_angular_velocity_) 164 | vel_error.head(3) += input_.desired_.angular_velocity_; 165 | 166 | intergral_error_.array() += error.array() * params_.time_step_; // TO-DO: What about the velocity error? 167 | 168 | Eigen::VectorXd ft = pid_params_.p_matrix_ * error + pid_params_.d_matrix_ * vel_error + pid_params_.i_matrix_ * intergral_error_; 169 | 170 | if (has_position_ || has_velocity_) 171 | output_.desired_.force_ = ft.tail(dim_); 172 | if (has_orientation_ || has_angular_velocity_) 173 | output_.desired_.torque_ = ft.head(3); 174 | } 175 | 176 | void Pid::SetParams(const ParamsPid& params) 177 | { 178 | pid_params_ = params; 179 | params_ = pid_params_.ToRobotParams(); 180 | } 181 | 182 | } // namespace low 183 | } // namespace robot_controllers 184 | 185 | CORRADE_PLUGIN_REGISTER(PidController, robot_controllers::low::Pid, "RobotControllers.AbstractController/1.0") 186 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | GNU GENERAL PUBLIC LICENSE 2 | Version 3, 29 June 2007 3 | 4 | Copyright (C) 2007 Free Software Foundation, Inc. 5 | Everyone is permitted to copy and distribute verbatim copies 6 | of this license document, but changing it is not allowed. 7 | 8 | Preamble 9 | 10 | The GNU General Public License is a free, copyleft license for 11 | software and other kinds of works. 12 | 13 | The licenses for most software and other practical works are designed 14 | to take away your freedom to share and change the works. By contrast, 15 | the GNU General Public License is intended to guarantee your freedom to 16 | share and change all versions of a program--to make sure it remains free 17 | software for all its users. We, the Free Software Foundation, use the 18 | GNU General Public License for most of our software; it applies also to 19 | any other work released this way by its authors. You can apply it to 20 | your programs, too. 21 | 22 | When we speak of free software, we are referring to freedom, not 23 | price. Our General Public Licenses are designed to make sure that you 24 | have the freedom to distribute copies of free software (and charge for 25 | them if you wish), that you receive source code or can get it if you 26 | want it, that you can change the software or use pieces of it in new 27 | free programs, and that you know you can do these things. 28 | 29 | To protect your rights, we need to prevent others from denying you 30 | these rights or asking you to surrender the rights. Therefore, you have 31 | certain responsibilities if you distribute copies of the software, or if 32 | you modify it: responsibilities to respect the freedom of others. 33 | 34 | For example, if you distribute copies of such a program, whether 35 | gratis or for a fee, you must pass on to the recipients the same 36 | freedoms that you received. You must make sure that they, too, receive 37 | or can get the source code. And you must show them these terms so they 38 | know their rights. 39 | 40 | Developers that use the GNU GPL protect your rights with two steps: 41 | (1) assert copyright on the software, and (2) offer you this License 42 | giving you legal permission to copy, distribute and/or modify it. 43 | 44 | For the developers' and authors' protection, the GPL clearly explains 45 | that there is no warranty for this free software. For both users' and 46 | authors' sake, the GPL requires that modified versions be marked as 47 | changed, so that their problems will not be attributed erroneously to 48 | authors of previous versions. 49 | 50 | Some devices are designed to deny users access to install or run 51 | modified versions of the software inside them, although the manufacturer 52 | can do so. This is fundamentally incompatible with the aim of 53 | protecting users' freedom to change the software. The systematic 54 | pattern of such abuse occurs in the area of products for individuals to 55 | use, which is precisely where it is most unacceptable. Therefore, we 56 | have designed this version of the GPL to prohibit the practice for those 57 | products. If such problems arise substantially in other domains, we 58 | stand ready to extend this provision to those domains in future versions 59 | of the GPL, as needed to protect the freedom of users. 60 | 61 | Finally, every program is threatened constantly by software patents. 62 | States should not allow patents to restrict development and use of 63 | software on general-purpose computers, but in those that do, we wish to 64 | avoid the special danger that patents applied to a free program could 65 | make it effectively proprietary. To prevent this, the GPL assures that 66 | patents cannot be used to render the program non-free. 67 | 68 | The precise terms and conditions for copying, distribution and 69 | modification follow. 70 | 71 | TERMS AND CONDITIONS 72 | 73 | 0. Definitions. 74 | 75 | "This License" refers to version 3 of the GNU General Public License. 76 | 77 | "Copyright" also means copyright-like laws that apply to other kinds of 78 | works, such as semiconductor masks. 79 | 80 | "The Program" refers to any copyrightable work licensed under this 81 | License. Each licensee is addressed as "you". "Licensees" and 82 | "recipients" may be individuals or organizations. 83 | 84 | To "modify" a work means to copy from or adapt all or part of the work 85 | in a fashion requiring copyright permission, other than the making of an 86 | exact copy. The resulting work is called a "modified version" of the 87 | earlier work or a work "based on" the earlier work. 88 | 89 | A "covered work" means either the unmodified Program or a work based 90 | on the Program. 91 | 92 | To "propagate" a work means to do anything with it that, without 93 | permission, would make you directly or secondarily liable for 94 | infringement under applicable copyright law, except executing it on a 95 | computer or modifying a private copy. Propagation includes copying, 96 | distribution (with or without modification), making available to the 97 | public, and in some countries other activities as well. 98 | 99 | To "convey" a work means any kind of propagation that enables other 100 | parties to make or receive copies. Mere interaction with a user through 101 | a computer network, with no transfer of a copy, is not conveying. 102 | 103 | An interactive user interface displays "Appropriate Legal Notices" 104 | to the extent that it includes a convenient and prominently visible 105 | feature that (1) displays an appropriate copyright notice, and (2) 106 | tells the user that there is no warranty for the work (except to the 107 | extent that warranties are provided), that licensees may convey the 108 | work under this License, and how to view a copy of this License. If 109 | the interface presents a list of user commands or options, such as a 110 | menu, a prominent item in the list meets this criterion. 111 | 112 | 1. Source Code. 113 | 114 | The "source code" for a work means the preferred form of the work 115 | for making modifications to it. "Object code" means any non-source 116 | form of a work. 117 | 118 | A "Standard Interface" means an interface that either is an official 119 | standard defined by a recognized standards body, or, in the case of 120 | interfaces specified for a particular programming language, one that 121 | is widely used among developers working in that language. 122 | 123 | The "System Libraries" of an executable work include anything, other 124 | than the work as a whole, that (a) is included in the normal form of 125 | packaging a Major Component, but which is not part of that Major 126 | Component, and (b) serves only to enable use of the work with that 127 | Major Component, or to implement a Standard Interface for which an 128 | implementation is available to the public in source code form. A 129 | "Major Component", in this context, means a major essential component 130 | (kernel, window system, and so on) of the specific operating system 131 | (if any) on which the executable work runs, or a compiler used to 132 | produce the work, or an object code interpreter used to run it. 133 | 134 | The "Corresponding Source" for a work in object code form means all 135 | the source code needed to generate, install, and (for an executable 136 | work) run the object code and to modify the work, including scripts to 137 | control those activities. However, it does not include the work's 138 | System Libraries, or general-purpose tools or generally available free 139 | programs which are used unmodified in performing those activities but 140 | which are not part of the work. For example, Corresponding Source 141 | includes interface definition files associated with source files for 142 | the work, and the source code for shared libraries and dynamically 143 | linked subprograms that the work is specifically designed to require, 144 | such as by intimate data communication or control flow between those 145 | subprograms and other parts of the work. 146 | 147 | The Corresponding Source need not include anything that users 148 | can regenerate automatically from other parts of the Corresponding 149 | Source. 150 | 151 | The Corresponding Source for a work in source code form is that 152 | same work. 153 | 154 | 2. Basic Permissions. 155 | 156 | All rights granted under this License are granted for the term of 157 | copyright on the Program, and are irrevocable provided the stated 158 | conditions are met. This License explicitly affirms your unlimited 159 | permission to run the unmodified Program. The output from running a 160 | covered work is covered by this License only if the output, given its 161 | content, constitutes a covered work. This License acknowledges your 162 | rights of fair use or other equivalent, as provided by copyright law. 163 | 164 | You may make, run and propagate covered works that you do not 165 | convey, without conditions so long as your license otherwise remains 166 | in force. You may convey covered works to others for the sole purpose 167 | of having them make modifications exclusively for you, or provide you 168 | with facilities for running those works, provided that you comply with 169 | the terms of this License in conveying all material for which you do 170 | not control copyright. Those thus making or running the covered works 171 | for you must do so exclusively on your behalf, under your direction 172 | and control, on terms that prohibit them from making any copies of 173 | your copyrighted material outside their relationship with you. 174 | 175 | Conveying under any other circumstances is permitted solely under 176 | the conditions stated below. Sublicensing is not allowed; section 10 177 | makes it unnecessary. 178 | 179 | 3. Protecting Users' Legal Rights From Anti-Circumvention Law. 180 | 181 | No covered work shall be deemed part of an effective technological 182 | measure under any applicable law fulfilling obligations under article 183 | 11 of the WIPO copyright treaty adopted on 20 December 1996, or 184 | similar laws prohibiting or restricting circumvention of such 185 | measures. 186 | 187 | When you convey a covered work, you waive any legal power to forbid 188 | circumvention of technological measures to the extent such circumvention 189 | is effected by exercising rights under this License with respect to 190 | the covered work, and you disclaim any intention to limit operation or 191 | modification of the work as a means of enforcing, against the work's 192 | users, your or third parties' legal rights to forbid circumvention of 193 | technological measures. 194 | 195 | 4. Conveying Verbatim Copies. 196 | 197 | You may convey verbatim copies of the Program's source code as you 198 | receive it, in any medium, provided that you conspicuously and 199 | appropriately publish on each copy an appropriate copyright notice; 200 | keep intact all notices stating that this License and any 201 | non-permissive terms added in accord with section 7 apply to the code; 202 | keep intact all notices of the absence of any warranty; and give all 203 | recipients a copy of this License along with the Program. 204 | 205 | You may charge any price or no price for each copy that you convey, 206 | and you may offer support or warranty protection for a fee. 207 | 208 | 5. Conveying Modified Source Versions. 209 | 210 | You may convey a work based on the Program, or the modifications to 211 | produce it from the Program, in the form of source code under the 212 | terms of section 4, provided that you also meet all of these conditions: 213 | 214 | a) The work must carry prominent notices stating that you modified 215 | it, and giving a relevant date. 216 | 217 | b) The work must carry prominent notices stating that it is 218 | released under this License and any conditions added under section 219 | 7. This requirement modifies the requirement in section 4 to 220 | "keep intact all notices". 221 | 222 | c) You must license the entire work, as a whole, under this 223 | License to anyone who comes into possession of a copy. This 224 | License will therefore apply, along with any applicable section 7 225 | additional terms, to the whole of the work, and all its parts, 226 | regardless of how they are packaged. This License gives no 227 | permission to license the work in any other way, but it does not 228 | invalidate such permission if you have separately received it. 229 | 230 | d) If the work has interactive user interfaces, each must display 231 | Appropriate Legal Notices; however, if the Program has interactive 232 | interfaces that do not display Appropriate Legal Notices, your 233 | work need not make them do so. 234 | 235 | A compilation of a covered work with other separate and independent 236 | works, which are not by their nature extensions of the covered work, 237 | and which are not combined with it such as to form a larger program, 238 | in or on a volume of a storage or distribution medium, is called an 239 | "aggregate" if the compilation and its resulting copyright are not 240 | used to limit the access or legal rights of the compilation's users 241 | beyond what the individual works permit. Inclusion of a covered work 242 | in an aggregate does not cause this License to apply to the other 243 | parts of the aggregate. 244 | 245 | 6. Conveying Non-Source Forms. 246 | 247 | You may convey a covered work in object code form under the terms 248 | of sections 4 and 5, provided that you also convey the 249 | machine-readable Corresponding Source under the terms of this License, 250 | in one of these ways: 251 | 252 | a) Convey the object code in, or embodied in, a physical product 253 | (including a physical distribution medium), accompanied by the 254 | Corresponding Source fixed on a durable physical medium 255 | customarily used for software interchange. 256 | 257 | b) Convey the object code in, or embodied in, a physical product 258 | (including a physical distribution medium), accompanied by a 259 | written offer, valid for at least three years and valid for as 260 | long as you offer spare parts or customer support for that product 261 | model, to give anyone who possesses the object code either (1) a 262 | copy of the Corresponding Source for all the software in the 263 | product that is covered by this License, on a durable physical 264 | medium customarily used for software interchange, for a price no 265 | more than your reasonable cost of physically performing this 266 | conveying of source, or (2) access to copy the 267 | Corresponding Source from a network server at no charge. 268 | 269 | c) Convey individual copies of the object code with a copy of the 270 | written offer to provide the Corresponding Source. This 271 | alternative is allowed only occasionally and noncommercially, and 272 | only if you received the object code with such an offer, in accord 273 | with subsection 6b. 274 | 275 | d) Convey the object code by offering access from a designated 276 | place (gratis or for a charge), and offer equivalent access to the 277 | Corresponding Source in the same way through the same place at no 278 | further charge. You need not require recipients to copy the 279 | Corresponding Source along with the object code. If the place to 280 | copy the object code is a network server, the Corresponding Source 281 | may be on a different server (operated by you or a third party) 282 | that supports equivalent copying facilities, provided you maintain 283 | clear directions next to the object code saying where to find the 284 | Corresponding Source. Regardless of what server hosts the 285 | Corresponding Source, you remain obligated to ensure that it is 286 | available for as long as needed to satisfy these requirements. 287 | 288 | e) Convey the object code using peer-to-peer transmission, provided 289 | you inform other peers where the object code and Corresponding 290 | Source of the work are being offered to the general public at no 291 | charge under subsection 6d. 292 | 293 | A separable portion of the object code, whose source code is excluded 294 | from the Corresponding Source as a System Library, need not be 295 | included in conveying the object code work. 296 | 297 | A "User Product" is either (1) a "consumer product", which means any 298 | tangible personal property which is normally used for personal, family, 299 | or household purposes, or (2) anything designed or sold for incorporation 300 | into a dwelling. In determining whether a product is a consumer product, 301 | doubtful cases shall be resolved in favor of coverage. For a particular 302 | product received by a particular user, "normally used" refers to a 303 | typical or common use of that class of product, regardless of the status 304 | of the particular user or of the way in which the particular user 305 | actually uses, or expects or is expected to use, the product. A product 306 | is a consumer product regardless of whether the product has substantial 307 | commercial, industrial or non-consumer uses, unless such uses represent 308 | the only significant mode of use of the product. 309 | 310 | "Installation Information" for a User Product means any methods, 311 | procedures, authorization keys, or other information required to install 312 | and execute modified versions of a covered work in that User Product from 313 | a modified version of its Corresponding Source. The information must 314 | suffice to ensure that the continued functioning of the modified object 315 | code is in no case prevented or interfered with solely because 316 | modification has been made. 317 | 318 | If you convey an object code work under this section in, or with, or 319 | specifically for use in, a User Product, and the conveying occurs as 320 | part of a transaction in which the right of possession and use of the 321 | User Product is transferred to the recipient in perpetuity or for a 322 | fixed term (regardless of how the transaction is characterized), the 323 | Corresponding Source conveyed under this section must be accompanied 324 | by the Installation Information. But this requirement does not apply 325 | if neither you nor any third party retains the ability to install 326 | modified object code on the User Product (for example, the work has 327 | been installed in ROM). 328 | 329 | The requirement to provide Installation Information does not include a 330 | requirement to continue to provide support service, warranty, or updates 331 | for a work that has been modified or installed by the recipient, or for 332 | the User Product in which it has been modified or installed. Access to a 333 | network may be denied when the modification itself materially and 334 | adversely affects the operation of the network or violates the rules and 335 | protocols for communication across the network. 336 | 337 | Corresponding Source conveyed, and Installation Information provided, 338 | in accord with this section must be in a format that is publicly 339 | documented (and with an implementation available to the public in 340 | source code form), and must require no special password or key for 341 | unpacking, reading or copying. 342 | 343 | 7. Additional Terms. 344 | 345 | "Additional permissions" are terms that supplement the terms of this 346 | License by making exceptions from one or more of its conditions. 347 | Additional permissions that are applicable to the entire Program shall 348 | be treated as though they were included in this License, to the extent 349 | that they are valid under applicable law. If additional permissions 350 | apply only to part of the Program, that part may be used separately 351 | under those permissions, but the entire Program remains governed by 352 | this License without regard to the additional permissions. 353 | 354 | When you convey a copy of a covered work, you may at your option 355 | remove any additional permissions from that copy, or from any part of 356 | it. (Additional permissions may be written to require their own 357 | removal in certain cases when you modify the work.) You may place 358 | additional permissions on material, added by you to a covered work, 359 | for which you have or can give appropriate copyright permission. 360 | 361 | Notwithstanding any other provision of this License, for material you 362 | add to a covered work, you may (if authorized by the copyright holders of 363 | that material) supplement the terms of this License with terms: 364 | 365 | a) Disclaiming warranty or limiting liability differently from the 366 | terms of sections 15 and 16 of this License; or 367 | 368 | b) Requiring preservation of specified reasonable legal notices or 369 | author attributions in that material or in the Appropriate Legal 370 | Notices displayed by works containing it; or 371 | 372 | c) Prohibiting misrepresentation of the origin of that material, or 373 | requiring that modified versions of such material be marked in 374 | reasonable ways as different from the original version; or 375 | 376 | d) Limiting the use for publicity purposes of names of licensors or 377 | authors of the material; or 378 | 379 | e) Declining to grant rights under trademark law for use of some 380 | trade names, trademarks, or service marks; or 381 | 382 | f) Requiring indemnification of licensors and authors of that 383 | material by anyone who conveys the material (or modified versions of 384 | it) with contractual assumptions of liability to the recipient, for 385 | any liability that these contractual assumptions directly impose on 386 | those licensors and authors. 387 | 388 | All other non-permissive additional terms are considered "further 389 | restrictions" within the meaning of section 10. If the Program as you 390 | received it, or any part of it, contains a notice stating that it is 391 | governed by this License along with a term that is a further 392 | restriction, you may remove that term. If a license document contains 393 | a further restriction but permits relicensing or conveying under this 394 | License, you may add to a covered work material governed by the terms 395 | of that license document, provided that the further restriction does 396 | not survive such relicensing or conveying. 397 | 398 | If you add terms to a covered work in accord with this section, you 399 | must place, in the relevant source files, a statement of the 400 | additional terms that apply to those files, or a notice indicating 401 | where to find the applicable terms. 402 | 403 | Additional terms, permissive or non-permissive, may be stated in the 404 | form of a separately written license, or stated as exceptions; 405 | the above requirements apply either way. 406 | 407 | 8. Termination. 408 | 409 | You may not propagate or modify a covered work except as expressly 410 | provided under this License. Any attempt otherwise to propagate or 411 | modify it is void, and will automatically terminate your rights under 412 | this License (including any patent licenses granted under the third 413 | paragraph of section 11). 414 | 415 | However, if you cease all violation of this License, then your 416 | license from a particular copyright holder is reinstated (a) 417 | provisionally, unless and until the copyright holder explicitly and 418 | finally terminates your license, and (b) permanently, if the copyright 419 | holder fails to notify you of the violation by some reasonable means 420 | prior to 60 days after the cessation. 421 | 422 | Moreover, your license from a particular copyright holder is 423 | reinstated permanently if the copyright holder notifies you of the 424 | violation by some reasonable means, this is the first time you have 425 | received notice of violation of this License (for any work) from that 426 | copyright holder, and you cure the violation prior to 30 days after 427 | your receipt of the notice. 428 | 429 | Termination of your rights under this section does not terminate the 430 | licenses of parties who have received copies or rights from you under 431 | this License. If your rights have been terminated and not permanently 432 | reinstated, you do not qualify to receive new licenses for the same 433 | material under section 10. 434 | 435 | 9. Acceptance Not Required for Having Copies. 436 | 437 | You are not required to accept this License in order to receive or 438 | run a copy of the Program. Ancillary propagation of a covered work 439 | occurring solely as a consequence of using peer-to-peer transmission 440 | to receive a copy likewise does not require acceptance. However, 441 | nothing other than this License grants you permission to propagate or 442 | modify any covered work. These actions infringe copyright if you do 443 | not accept this License. Therefore, by modifying or propagating a 444 | covered work, you indicate your acceptance of this License to do so. 445 | 446 | 10. Automatic Licensing of Downstream Recipients. 447 | 448 | Each time you convey a covered work, the recipient automatically 449 | receives a license from the original licensors, to run, modify and 450 | propagate that work, subject to this License. You are not responsible 451 | for enforcing compliance by third parties with this License. 452 | 453 | An "entity transaction" is a transaction transferring control of an 454 | organization, or substantially all assets of one, or subdividing an 455 | organization, or merging organizations. If propagation of a covered 456 | work results from an entity transaction, each party to that 457 | transaction who receives a copy of the work also receives whatever 458 | licenses to the work the party's predecessor in interest had or could 459 | give under the previous paragraph, plus a right to possession of the 460 | Corresponding Source of the work from the predecessor in interest, if 461 | the predecessor has it or can get it with reasonable efforts. 462 | 463 | You may not impose any further restrictions on the exercise of the 464 | rights granted or affirmed under this License. For example, you may 465 | not impose a license fee, royalty, or other charge for exercise of 466 | rights granted under this License, and you may not initiate litigation 467 | (including a cross-claim or counterclaim in a lawsuit) alleging that 468 | any patent claim is infringed by making, using, selling, offering for 469 | sale, or importing the Program or any portion of it. 470 | 471 | 11. Patents. 472 | 473 | A "contributor" is a copyright holder who authorizes use under this 474 | License of the Program or a work on which the Program is based. The 475 | work thus licensed is called the contributor's "contributor version". 476 | 477 | A contributor's "essential patent claims" are all patent claims 478 | owned or controlled by the contributor, whether already acquired or 479 | hereafter acquired, that would be infringed by some manner, permitted 480 | by this License, of making, using, or selling its contributor version, 481 | but do not include claims that would be infringed only as a 482 | consequence of further modification of the contributor version. For 483 | purposes of this definition, "control" includes the right to grant 484 | patent sublicenses in a manner consistent with the requirements of 485 | this License. 486 | 487 | Each contributor grants you a non-exclusive, worldwide, royalty-free 488 | patent license under the contributor's essential patent claims, to 489 | make, use, sell, offer for sale, import and otherwise run, modify and 490 | propagate the contents of its contributor version. 491 | 492 | In the following three paragraphs, a "patent license" is any express 493 | agreement or commitment, however denominated, not to enforce a patent 494 | (such as an express permission to practice a patent or covenant not to 495 | sue for patent infringement). To "grant" such a patent license to a 496 | party means to make such an agreement or commitment not to enforce a 497 | patent against the party. 498 | 499 | If you convey a covered work, knowingly relying on a patent license, 500 | and the Corresponding Source of the work is not available for anyone 501 | to copy, free of charge and under the terms of this License, through a 502 | publicly available network server or other readily accessible means, 503 | then you must either (1) cause the Corresponding Source to be so 504 | available, or (2) arrange to deprive yourself of the benefit of the 505 | patent license for this particular work, or (3) arrange, in a manner 506 | consistent with the requirements of this License, to extend the patent 507 | license to downstream recipients. "Knowingly relying" means you have 508 | actual knowledge that, but for the patent license, your conveying the 509 | covered work in a country, or your recipient's use of the covered work 510 | in a country, would infringe one or more identifiable patents in that 511 | country that you have reason to believe are valid. 512 | 513 | If, pursuant to or in connection with a single transaction or 514 | arrangement, you convey, or propagate by procuring conveyance of, a 515 | covered work, and grant a patent license to some of the parties 516 | receiving the covered work authorizing them to use, propagate, modify 517 | or convey a specific copy of the covered work, then the patent license 518 | you grant is automatically extended to all recipients of the covered 519 | work and works based on it. 520 | 521 | A patent license is "discriminatory" if it does not include within 522 | the scope of its coverage, prohibits the exercise of, or is 523 | conditioned on the non-exercise of one or more of the rights that are 524 | specifically granted under this License. You may not convey a covered 525 | work if you are a party to an arrangement with a third party that is 526 | in the business of distributing software, under which you make payment 527 | to the third party based on the extent of your activity of conveying 528 | the work, and under which the third party grants, to any of the 529 | parties who would receive the covered work from you, a discriminatory 530 | patent license (a) in connection with copies of the covered work 531 | conveyed by you (or copies made from those copies), or (b) primarily 532 | for and in connection with specific products or compilations that 533 | contain the covered work, unless you entered into that arrangement, 534 | or that patent license was granted, prior to 28 March 2007. 535 | 536 | Nothing in this License shall be construed as excluding or limiting 537 | any implied license or other defenses to infringement that may 538 | otherwise be available to you under applicable patent law. 539 | 540 | 12. No Surrender of Others' Freedom. 541 | 542 | If conditions are imposed on you (whether by court order, agreement or 543 | otherwise) that contradict the conditions of this License, they do not 544 | excuse you from the conditions of this License. If you cannot convey a 545 | covered work so as to satisfy simultaneously your obligations under this 546 | License and any other pertinent obligations, then as a consequence you may 547 | not convey it at all. For example, if you agree to terms that obligate you 548 | to collect a royalty for further conveying from those to whom you convey 549 | the Program, the only way you could satisfy both those terms and this 550 | License would be to refrain entirely from conveying the Program. 551 | 552 | 13. Use with the GNU Affero General Public License. 553 | 554 | Notwithstanding any other provision of this License, you have 555 | permission to link or combine any covered work with a work licensed 556 | under version 3 of the GNU Affero General Public License into a single 557 | combined work, and to convey the resulting work. The terms of this 558 | License will continue to apply to the part which is the covered work, 559 | but the special requirements of the GNU Affero General Public License, 560 | section 13, concerning interaction through a network will apply to the 561 | combination as such. 562 | 563 | 14. Revised Versions of this License. 564 | 565 | The Free Software Foundation may publish revised and/or new versions of 566 | the GNU General Public License from time to time. Such new versions will 567 | be similar in spirit to the present version, but may differ in detail to 568 | address new problems or concerns. 569 | 570 | Each version is given a distinguishing version number. If the 571 | Program specifies that a certain numbered version of the GNU General 572 | Public License "or any later version" applies to it, you have the 573 | option of following the terms and conditions either of that numbered 574 | version or of any later version published by the Free Software 575 | Foundation. If the Program does not specify a version number of the 576 | GNU General Public License, you may choose any version ever published 577 | by the Free Software Foundation. 578 | 579 | If the Program specifies that a proxy can decide which future 580 | versions of the GNU General Public License can be used, that proxy's 581 | public statement of acceptance of a version permanently authorizes you 582 | to choose that version for the Program. 583 | 584 | Later license versions may give you additional or different 585 | permissions. However, no additional obligations are imposed on any 586 | author or copyright holder as a result of your choosing to follow a 587 | later version. 588 | 589 | 15. Disclaimer of Warranty. 590 | 591 | THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY 592 | APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT 593 | HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY 594 | OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, 595 | THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 596 | PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM 597 | IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF 598 | ALL NECESSARY SERVICING, REPAIR OR CORRECTION. 599 | 600 | 16. Limitation of Liability. 601 | 602 | IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING 603 | WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS 604 | THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY 605 | GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE 606 | USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF 607 | DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD 608 | PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), 609 | EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF 610 | SUCH DAMAGES. 611 | 612 | 17. Interpretation of Sections 15 and 16. 613 | 614 | If the disclaimer of warranty and limitation of liability provided 615 | above cannot be given local legal effect according to their terms, 616 | reviewing courts shall apply local law that most closely approximates 617 | an absolute waiver of all civil liability in connection with the 618 | Program, unless a warranty or assumption of liability accompanies a 619 | copy of the Program in return for a fee. 620 | 621 | END OF TERMS AND CONDITIONS 622 | 623 | How to Apply These Terms to Your New Programs 624 | 625 | If you develop a new program, and you want it to be of the greatest 626 | possible use to the public, the best way to achieve this is to make it 627 | free software which everyone can redistribute and change under these terms. 628 | 629 | To do so, attach the following notices to the program. It is safest 630 | to attach them to the start of each source file to most effectively 631 | state the exclusion of warranty; and each file should have at least 632 | the "copyright" line and a pointer to where the full notice is found. 633 | 634 | 635 | Copyright (C) 636 | 637 | This program is free software: you can redistribute it and/or modify 638 | it under the terms of the GNU General Public License as published by 639 | the Free Software Foundation, either version 3 of the License, or 640 | (at your option) any later version. 641 | 642 | This program is distributed in the hope that it will be useful, 643 | but WITHOUT ANY WARRANTY; without even the implied warranty of 644 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 645 | GNU General Public License for more details. 646 | 647 | You should have received a copy of the GNU General Public License 648 | along with this program. If not, see . 649 | 650 | Also add information on how to contact you by electronic and paper mail. 651 | 652 | If the program does terminal interaction, make it output a short 653 | notice like this when it starts in an interactive mode: 654 | 655 | Copyright (C) 656 | This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. 657 | This is free software, and you are welcome to redistribute it 658 | under certain conditions; type `show c' for details. 659 | 660 | The hypothetical commands `show w' and `show c' should show the appropriate 661 | parts of the General Public License. Of course, your program's commands 662 | might be different; for a GUI interface, you would use an "about box". 663 | 664 | You should also get your employer (if you work as a programmer) or school, 665 | if any, to sign a "copyright disclaimer" for the program, if necessary. 666 | For more information on this, and how to apply and follow the GNU GPL, see 667 | . 668 | 669 | The GNU General Public License does not permit incorporating your program 670 | into proprietary programs. If your program is a subroutine library, you 671 | may consider it more useful to permit linking proprietary applications with 672 | the library. If this is what you want to do, use the GNU Lesser General 673 | Public License instead of this License. But first, please read 674 | . --------------------------------------------------------------------------------