diff --git a/cpp/scenario/controllers/CMakeLists.txt b/cpp/scenario/controllers/CMakeLists.txt index d0fc361ed..59a141eb3 100644 --- a/cpp/scenario/controllers/CMakeLists.txt +++ b/cpp/scenario/controllers/CMakeLists.txt @@ -42,12 +42,42 @@ target_include_directories(Controller INTERFACE set_target_properties(Controller PROPERTIES PUBLIC_HEADER "${CONTROLLER_HDRS}") +# ======================= +# ComputedTorqueFixedBase +# ======================= +add_library(ComputedTorqueFixedBase + include/scenario/controllers/ComputedTorqueFixedBase.h + src/ComputedTorqueFixedBase.cpp) + +target_link_libraries(ComputedTorqueFixedBase + PUBLIC + Controller + PRIVATE + ScenarioGazebo + Eigen3::Eigen + ignition-gazebo3::core + iDynTree::idyntree-core + iDynTree::idyntree-model + iDynTree::idyntree-modelio-urdf + iDynTree::idyntree-high-level) + +target_include_directories(ComputedTorqueFixedBase PUBLIC + $ + $) + +set_target_properties(ComputedTorqueFixedBase PROPERTIES + PUBLIC_HEADER include/scenario/controllers/ComputedTorqueFixedBase.h) + +# =================== +# Install the targets +# =================== if(NOT CMAKE_BUILD_TYPE STREQUAL "PyPI") install( TARGETS Controller + ComputedTorqueFixedBase EXPORT scenario LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} diff --git a/cpp/scenario/controllers/include/scenario/controllers/ComputedTorqueFixedBase.h b/cpp/scenario/controllers/include/scenario/controllers/ComputedTorqueFixedBase.h new file mode 100644 index 000000000..2b7022ec8 --- /dev/null +++ b/cpp/scenario/controllers/include/scenario/controllers/ComputedTorqueFixedBase.h @@ -0,0 +1,77 @@ +/* + * Copyright (C) 2020 Istituto Italiano di Tecnologia (IIT) + * All rights reserved. + * + * This project is dual licensed under LGPL v2.1+ or Apache License. + * + * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + * + * This software may be modified and distributed under the terms of the + * GNU Lesser General Public License v2.1 or any later version. + * + * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef SCENARIO_CONTROLLERS_COMPUTEDTORQUEFIXEDBASE_H +#define SCENARIO_CONTROLLERS_COMPUTEDTORQUEFIXEDBASE_H + +#include "scenario/controllers/Controller.h" +#include "scenario/controllers/References.h" + +#include +#include +#include +#include + +namespace scenario { + namespace gazebo { + class Model; + } // namespace gazebo + namespace controllers { + class ControllersFactory; + class ComputedTorqueFixedBase; + } // namespace controllers +} // namespace scenario + +class scenario::controllers::ComputedTorqueFixedBase final + : public scenario::controllers::Controller + , public scenario::controllers::UseScenarioModel + , public scenario::controllers::SetJointReferences +{ +public: + ComputedTorqueFixedBase() = delete; + ComputedTorqueFixedBase(const std::string& urdfFile, + std::shared_ptr model, + const std::vector& kp, + const std::vector& kd, + const std::vector& controlledJoints, + const std::array gravity = g); + ~ComputedTorqueFixedBase() override; + + bool initialize() override; + bool step(const StepSize& dt) override; + bool terminate() override; + + bool updateStateFromModel() override; + + const std::vector& controlledJoints() override; + bool setJointReferences(const JointReferences& jointReferences) override; + +private: + class Impl; + std::unique_ptr pImpl; +}; + +#endif // SCENARIO_CONTROLLERS_COMPUTEDTORQUEFIXEDBASE_H diff --git a/cpp/scenario/controllers/src/ComputedTorqueFixedBase.cpp b/cpp/scenario/controllers/src/ComputedTorqueFixedBase.cpp new file mode 100644 index 000000000..4655e818b --- /dev/null +++ b/cpp/scenario/controllers/src/ComputedTorqueFixedBase.cpp @@ -0,0 +1,362 @@ +/* + * Copyright (C) 2020 Istituto Italiano di Tecnologia (IIT) + * All rights reserved. + * + * This project is dual licensed under LGPL v2.1+ or Apache License. + * + * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + * + * This software may be modified and distributed under the terms of the + * GNU Lesser General Public License v2.1 or any later version. + * + * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include "scenario/controllers/ComputedTorqueFixedBase.h" +#include "scenario/controllers/References.h" +#include "scenario/gazebo/Joint.h" +#include "scenario/gazebo/Log.h" +#include "scenario/gazebo/Model.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace scenario::controllers; + +class ComputedTorqueFixedBase::Impl +{ +public: + class Buffers; + + std::string urdfFile; + + struct + { + std::vector kp; + std::vector kd; + std::array gravity; + std::unordered_map controlMode; + } initialValues; + + JointReferences jointReferences; + std::unique_ptr buffers; + std::unique_ptr kinDyn; + + static Eigen::Map toEigen(std::vector& vector) + { + return {vector.data(), Eigen::Index(vector.size())}; + } +}; + +class ComputedTorqueFixedBase::Impl::Buffers +{ +public: + Buffers(const unsigned controlledDofs = 0) + { + jointPositions.resize(controlledDofs); + jointVelocities.resize(controlledDofs); + massMatrix.resize(controlledDofs + 6, controlledDofs + 6); + + kp = Eigen::ArrayXd(controlledDofs); + kd = Eigen::ArrayXd(controlledDofs); + + torques = Eigen::VectorXd(controlledDofs); + dds_star = Eigen::VectorXd(controlledDofs); + positionError = Eigen::VectorXd(controlledDofs); + velocityError = Eigen::VectorXd(controlledDofs); + + torquesVector.reserve(controlledDofs); + } + + iDynTree::Vector3 gravity = {g.data(), 3}; + iDynTree::MatrixDynSize massMatrix; + iDynTree::VectorDynSize jointPositions; + iDynTree::VectorDynSize jointVelocities; + iDynTree::FreeFloatingGeneralizedTorques biasForces; + + Eigen::ArrayXd kp; + Eigen::ArrayXd kd; + + Eigen::VectorXd torques; + Eigen::VectorXd dds_star; + Eigen::VectorXd positionError; + Eigen::VectorXd velocityError; + + std::vector torquesVector; +}; + +ComputedTorqueFixedBase::ComputedTorqueFixedBase( + const std::string& urdfFile, + std::shared_ptr model, + const std::vector& kp, + const std::vector& kd, + const std::vector& controlledJoints, + const std::array gravity) + : Controller() + , UseScenarioModel() + , SetJointReferences() + , pImpl{std::make_unique()} +{ + m_model = model; + pImpl->urdfFile = urdfFile; + m_controlledJoints = controlledJoints; + assert(m_model->dofs() == controlledJoints.size() + || controlledJoints.empty()); + + pImpl->initialValues.gravity = gravity; + + pImpl->initialValues.kp = kp; + pImpl->initialValues.kd = kd; + assert(m_model->dofs() == kp.size()); + assert(kp.size() == kd.size()); +} + +ComputedTorqueFixedBase::~ComputedTorqueFixedBase() {} + +bool ComputedTorqueFixedBase::initialize() +{ + gymppDebug << "Initializing ComputedTorqueFixedBaseCpp" << std::endl; + + if (pImpl->kinDyn) { + gymppWarning + << "The KinDynComputations object has been already initialized" + << std::endl; + return true; + } + + if (!(m_model && m_model->valid())) { + gymppError << "Couldn't initialize controller. Model not valid." + << std::endl; + return false; + } + + if (m_controlledJoints.size() != m_model->dofs() + || m_controlledJoints.empty()) { + gymppError << "The list of controlled joints is not valid" << std::endl; + return false; + } + + if (m_controlledJoints.empty()) { + gymppDebug << "No list of controlled joints. Controlling all the " + "robots joints." + << std::endl; + + // Read the joint names from the robot object. + // This is useful to use the same joint serialization in the vectorized + // methods. + m_controlledJoints = m_model->jointNames(); + } + + for (auto& joint : m_model->joints(m_controlledJoints)) { + if (joint->dofs() != 1) { + gymppError << "Joint '" << joint->name() + << "' does not have 1 DoF and is not supported" + << std::endl; + return false; + } + } + + iDynTree::ModelLoader loader; + if (!loader.loadReducedModelFromFile(pImpl->urdfFile, m_controlledJoints)) { + gymppError << "Failed to load reduced model from the urdf file" + << std::endl; + return false; + } + + pImpl->kinDyn = std::make_unique(); + pImpl->kinDyn->setFrameVelocityRepresentation( + iDynTree::MIXED_REPRESENTATION); + + if (!pImpl->kinDyn->loadRobotModel(loader.model())) { + gymppError << "Failed to insert model in the KinDynComputations object" + << std::endl; + return false; + } + + // Set controlled joints in torque control mode + for (auto& joint : m_model->joints(m_controlledJoints)) { + pImpl->initialValues.controlMode[joint->name()] = joint->controlMode(); + + if (!joint->setControlMode(base::JointControlMode::Force)) { + gymppError << "Failed to control joint '" << joint->name() + << "' in Force" << std::endl; + return false; + } + } + + // Initialize buffers + gymppDebug << "Controlling " << m_controlledJoints.size() << " DoFs" + << std::endl; + pImpl->buffers = std::make_unique(m_controlledJoints.size()); + + pImpl->buffers->kp = Impl::toEigen(pImpl->initialValues.kp); + pImpl->buffers->kd = Impl::toEigen(pImpl->initialValues.kd); + pImpl->buffers->biasForces.resize(loader.model()); + + // Set the gravity + pImpl->buffers->gravity[0] = pImpl->initialValues.gravity[0]; + pImpl->buffers->gravity[1] = pImpl->initialValues.gravity[1]; + pImpl->buffers->gravity[2] = pImpl->initialValues.gravity[2]; + + return true; +} + +bool ComputedTorqueFixedBase::step(const Controller::StepSize& /*dt*/) +{ + // =================== + // Intermediate Values + // =================== + + const auto nrControlledDofs = pImpl->buffers->jointPositions.size(); + + auto Mfloating = iDynTree::toEigen(pImpl->buffers->massMatrix); + + auto h = iDynTree::toEigen(pImpl->buffers->biasForces.jointTorques()); + auto M = Mfloating.bottomRightCorner(nrControlledDofs, nrControlledDofs); + assert(h.size() == nrControlledDofs); + assert(M.size() == nrControlledDofs * nrControlledDofs); + + auto s = iDynTree::toEigen(pImpl->buffers->jointPositions); + auto ds = iDynTree::toEigen(pImpl->buffers->jointVelocities); + assert(s.size() == nrControlledDofs); + assert(ds.size() == nrControlledDofs); + + auto s_ref = Impl::toEigen(pImpl->jointReferences.position); + auto ds_ref = Impl::toEigen(pImpl->jointReferences.velocity); + auto dds_ref = Impl::toEigen(pImpl->jointReferences.acceleration); + assert(s_ref.size() == nrControlledDofs); + assert(ds_ref.size() == nrControlledDofs); + assert(dds_ref.size() == nrControlledDofs); + + auto& kp = pImpl->buffers->kp; + auto& kd = pImpl->buffers->kd; + auto& s_tilde = pImpl->buffers->positionError; + auto& ds_tilde = pImpl->buffers->velocityError; + assert(kp.size() == nrControlledDofs); + assert(kd.size() == nrControlledDofs); + assert(s_tilde.size() == nrControlledDofs); + assert(ds_tilde.size() == nrControlledDofs); + + auto& tau = pImpl->buffers->torques; + auto& dds_star = pImpl->buffers->dds_star; + assert(tau.size() == nrControlledDofs); + assert(dds_star.size() == nrControlledDofs); + + // =========== + // Control Law + // =========== + + // Compute errors + s_tilde = s - s_ref; + ds_tilde = ds - ds_ref; + + // Compute the acceleration + dds_star = dds_ref.array() - kp * s_tilde.array() - kd * ds_tilde.array(); + + // Compute the torque + tau = M * dds_star + h; + + pImpl->buffers->torquesVector = std::vector( + pImpl->buffers->torques.data(), + pImpl->buffers->torques.data() + pImpl->buffers->torques.size()); + + if (!m_model->setJointGeneralizedForceTargets(pImpl->buffers->torquesVector, + m_controlledJoints)) { + gymppError << "Failed to set joint forces" << std::endl; + return false; + } + + return true; +} + +bool ComputedTorqueFixedBase::terminate() +{ + bool ok = true; + + for (const auto& [jointName, controlMode] : + pImpl->initialValues.controlMode) { + + auto joint = m_model->getJoint(jointName); + + if (!joint->setControlMode(controlMode)) { + gymppError << "Failed to restore original control mode of joint '" + << jointName << "'" << std::endl; + ok = ok && false; + } + } + + pImpl->kinDyn.reset(); + pImpl->buffers.reset(); + return ok; +} + +bool ComputedTorqueFixedBase::updateStateFromModel() +{ + assert(m_model->jointPositions(m_controlledJoints).size() + == pImpl->buffers->jointPositions.size()); + assert(m_model->jointVelocities(m_controlledJoints).size() + == pImpl->buffers->jointVelocities.size()); + + for (unsigned i = 0; i < m_controlledJoints.size(); ++i) { + // Get the joint + const auto& jointName = m_controlledJoints[i]; + auto joint = m_model->getJoint(jointName); + assert(joint->dofs() == 1); + + // Update the buffers + pImpl->buffers->jointPositions.setVal(i, joint->position()); + pImpl->buffers->jointVelocities.setVal(i, joint->velocity()); + } + + if (!pImpl->kinDyn->setRobotState(pImpl->buffers->jointPositions, + pImpl->buffers->jointVelocities, + pImpl->buffers->gravity)) { + gymppError << "Failed to set the robot state" << std::endl; + return false; + } + + if (!pImpl->kinDyn->getFreeFloatingMassMatrix(pImpl->buffers->massMatrix)) { + gymppError << "Failed to get the mass matrix" << std::endl; + return false; + } + + if (!pImpl->kinDyn->generalizedBiasForces(pImpl->buffers->biasForces)) { + gymppError << "Failed to get the bias forces " << std::endl; + return false; + } + + return true; +} + +const std::vector& ComputedTorqueFixedBase::controlledJoints() +{ + return m_controlledJoints; +} + +bool ComputedTorqueFixedBase::setJointReferences( + const JointReferences& jointReferences) +{ + pImpl->jointReferences = jointReferences; + return pImpl->jointReferences.valid(); +};