Skip to content

Commit

Permalink
Merge branch 'master' into bindings/toml
Browse files Browse the repository at this point in the history
  • Loading branch information
GiulioRomualdi authored Oct 26, 2021
2 parents 3d4f08b + 9303539 commit 1e3a6fb
Show file tree
Hide file tree
Showing 12 changed files with 503 additions and 6 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ All notable changes to this project are documented in this file.
- Implement Python bindings for the TSID component (https://github.com/ami-iit/bipedal-locomotion-framework/pull/428)
- Add the possibility to set the name of each element of a variable stored in the variables handler (https://github.com/ami-iit/bipedal-locomotion-framework/pull/429)
- Develop the python bindings for toml implementation of the parameters handler (https://github.com/ami-iit/bipedal-locomotion-framework/pull/432)
- Implement the VariableRegularizationTask in TSID (https://github.com/ami-iit/bipedal-locomotion-framework/pull/431)

### Changed
### Fix
Expand Down
4 changes: 2 additions & 2 deletions bindings/python/TSID/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@ if(FRAMEWORK_COMPILE_TSID)

add_bipedal_locomotion_python_module(
NAME TSIDBindings
SOURCES src/BaseDynamicsTask.cpp src/CoMTask.cpp src/FeasibleContactWrenchTask.cpp src/JointDynamicsTask.cpp src/JointTrackingTask.cpp src/Module.cpp src/QPTSID.cpp src/SE3Task.cpp src/SO3Task.cpp src/TaskSpaceInverseDynamics.cpp src/TSIDLinearTask.cpp
HEADERS ${H_PREFIX}/BaseDynamicsTask.h ${H_PREFIX}/CoMTask.h ${H_PREFIX}/FeasibleContactWrenchTask.h ${H_PREFIX}/JointDynamicsTask.h ${H_PREFIX}/JointTrackingTask.h ${H_PREFIX}/Module.h ${H_PREFIX}/QPTSID.h ${H_PREFIX}/SE3Task.h ${H_PREFIX}/SO3Task.h ${H_PREFIX}/TaskSpaceInverseDynamics.h ${H_PREFIX}/TSIDLinearTask.h
SOURCES src/BaseDynamicsTask.cpp src/CoMTask.cpp src/FeasibleContactWrenchTask.cpp src/JointDynamicsTask.cpp src/JointTrackingTask.cpp src/Module.cpp src/QPTSID.cpp src/SE3Task.cpp src/SO3Task.cpp src/TaskSpaceInverseDynamics.cpp src/TSIDLinearTask.cpp src/VariableRegularizationTask.cpp
HEADERS ${H_PREFIX}/BaseDynamicsTask.h ${H_PREFIX}/CoMTask.h ${H_PREFIX}/FeasibleContactWrenchTask.h ${H_PREFIX}/JointDynamicsTask.h ${H_PREFIX}/JointTrackingTask.h ${H_PREFIX}/Module.h ${H_PREFIX}/QPTSID.h ${H_PREFIX}/SE3Task.h ${H_PREFIX}/SO3Task.h ${H_PREFIX}/TaskSpaceInverseDynamics.h ${H_PREFIX}/TSIDLinearTask.h ${H_PREFIX}/VariableRegularizationTask.h
LINK_LIBRARIES BipedalLocomotion::TSID
TESTS tests/test_TSID.py
)
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
/**
* @file VariableRegularizationTask.h
* @authors Giulio Romualdi
* @copyright 2021 Istituto Italiano di Tecnologia (IIT). This software may be modified and
* distributed under the terms of the GNU Lesser General Public License v2.1 or any later version.
*/

#ifndef BIPEDAL_LOCOMOTION_BINDINGS_TSID_VARIABLE_REGULARIZATION_TASK_H
#define BIPEDAL_LOCOMOTION_BINDINGS_TSID_VARIABLE_REGULARIZATION_TASK_H

#include <pybind11/pybind11.h>

namespace BipedalLocomotion
{
namespace bindings
{
namespace TSID
{

void CreateVariableRegularizationTask(pybind11::module& module);

} // namespace TSID
} // namespace bindings
} // namespace BipedalLocomotion

#endif // BIPEDAL_LOCOMOTION_BINDINGS_TSID_VARIABLE_REGULARIZATION_TASK_H
3 changes: 0 additions & 3 deletions bindings/python/TSID/src/JointTrackingTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,6 @@ void CreateJointTrackingTask(pybind11::module& module)
"JointTrackingTask")
.def(py::init())
.def("set_kin_dyn", &JointTrackingTask::setKinDyn, py::arg("kin_dyn"))
.def("set_variables_handler",
&JointTrackingTask::setVariablesHandler,
py::arg("variables_handler"))
.def("set_set_point",
py::overload_cast<Eigen::Ref<const Eigen::VectorXd>>(&JointTrackingTask::setSetPoint),
py::arg("joint_position"))
Expand Down
3 changes: 3 additions & 0 deletions bindings/python/TSID/src/Module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
* distributed under the terms of the GNU Lesser General Public License v2.1 or any later version.
*/

#include "BipedalLocomotion/bindings/System/VariablesHandler.h"
#include <pybind11/pybind11.h>

#include <BipedalLocomotion/bindings/TSID/BaseDynamicsTask.h>
Expand All @@ -18,6 +19,7 @@
#include <BipedalLocomotion/bindings/TSID/SO3Task.h>
#include <BipedalLocomotion/bindings/TSID/TSIDLinearTask.h>
#include <BipedalLocomotion/bindings/TSID/TaskSpaceInverseDynamics.h>
#include <BipedalLocomotion/bindings/TSID/VariableRegularizationTask.h>

namespace BipedalLocomotion
{
Expand All @@ -38,6 +40,7 @@ void CreateModule(pybind11::module& module)
CreateJointDynamicsTask(module);
CreateFeasibleContactWrenchTask(module);
CreateTaskSpaceInverseDynamics(module);
CreateVariableRegularizationTask(module);
CreateQPTSID(module);
CreateQPFixedBaseTSID(module);
}
Expand Down
37 changes: 37 additions & 0 deletions bindings/python/TSID/src/VariableRegularizationTask.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/**
* @file VariableRegularizationTask.cpp
* @authors Giulio Romualdi
* @copyright 2021 Istituto Italiano di Tecnologia (IIT). This software may be modified and
* distributed under the terms of the GNU Lesser General Public License v2.1 or any later version.
*/

#include <pybind11/eigen.h>
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>

#include <BipedalLocomotion/TSID/TSIDLinearTask.h>
#include <BipedalLocomotion/TSID/VariableRegularizationTask.h>
#include <BipedalLocomotion/bindings/TSID/VariableRegularizationTask.h>

namespace BipedalLocomotion
{
namespace bindings
{
namespace TSID
{

void CreateVariableRegularizationTask(pybind11::module& module)
{
namespace py = ::pybind11;
using namespace ::BipedalLocomotion::TSID;

py::class_<VariableRegularizationTask,
std::shared_ptr<VariableRegularizationTask>,
TSIDLinearTask>(module, "VariableRegularizationTask")
.def(py::init())
.def("set_set_point", &VariableRegularizationTask::setSetPoint, py::arg("set_point"));
}

} // namespace TSID
} // namespace bindings
} // namespace BipedalLocomotion
33 changes: 33 additions & 0 deletions bindings/python/TSID/tests/test_TSID.py
Original file line number Diff line number Diff line change
Expand Up @@ -216,3 +216,36 @@ def test_dynamics():
assert joint_dynamics_task.set_kin_dyn(kindyn_desc.kindyn)
assert joint_dynamics_task.initialize(param_handler=param_handler)
assert joint_dynamics_task.set_variables_handler(variables_handler=var_handler)

def test_variable_regularization_task():

# get kindyn
joints_list, kindyn_desc = get_kindyn()

# Set the parameters
param_handler_1 = blf.parameters_handler.StdParametersHandler()
param_handler_1.set_parameter_string(name="variable_name", value="variable_1")
param_handler_1.set_parameter_int(name="variable_size", value=15)

# Set the parameters
param_handler_2 = blf.parameters_handler.StdParametersHandler()
param_handler_2.set_parameter_string(name="variable_name", value="variable_2")
param_handler_2.set_parameter_int(name="variable_size", value=3)
param_handler_2.set_parameter_vector_string(name="elements_name",
value = ["huey", "dewey", "louie"])


var_handler = blf.system.VariablesHandler()
var_handler.add_variable("variable_1", 15)
var_handler.add_variable("variable_2", ["donald", "huey", "dewey", "louie", "daisy"])

# Initialize the task
regularizer_1 = blf.tsid.VariableRegularizationTask()
assert regularizer_1.initialize(param_handler=param_handler_1)
assert regularizer_1.set_variables_handler(variables_handler=var_handler)
assert regularizer_1.set_variables_handler(variables_handler=var_handler)

# Initialize the task
regularizer_2 = blf.tsid.VariableRegularizationTask()
assert regularizer_2.initialize(param_handler=param_handler_2)
assert regularizer_2.set_variables_handler(variables_handler=var_handler)
2 changes: 2 additions & 0 deletions src/TSID/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,12 @@ if(FRAMEWORK_COMPILE_TSID)
${H_PREFIX}/BaseDynamicsTask.h ${H_PREFIX}/JointDynamicsTask.h
${H_PREFIX}/TaskSpaceInverseDynamics.h
${H_PREFIX}/FeasibleContactWrenchTask.h
${H_PREFIX}/VariableRegularizationTask.h
${H_PREFIX}/QPFixedBaseTSID.h ${H_PREFIX}/QPTSID.h
SOURCES src/SO3Task.cpp src/SE3Task.cpp src/JointTrackingTask.cpp src/CoMTask.cpp
src/BaseDynamicsTask.cpp src/JointDynamicsTask.cpp
src/FeasibleContactWrenchTask.cpp
src/VariableRegularizationTask.cpp
src/QPFixedBaseTSID.cpp src/QPTSID.cpp
PUBLIC_LINK_LIBRARIES Eigen3::Eigen
BipedalLocomotion::Contacts
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
/**
* @file VariableRegularizationTask.h
* @authors Giulio Romualdi
* @copyright 2021 Istituto Italiano di Tecnologia (IIT). This software may be modified and
* distributed under the terms of the GNU Lesser General Public License v2.1 or any later version.
*/

#ifndef BIPEDAL_LOCOMOTION_TSID_VARIABLE_REGULARIZATION_TASK_H
#define BIPEDAL_LOCOMOTION_TSID_VARIABLE_REGULARIZATION_TASK_H

#include <BipedalLocomotion/TSID/TSIDLinearTask.h>

namespace BipedalLocomotion
{
namespace TSID
{

/**
* VariableRegularizationTask is a concrete implementation of the Task. Please use this element if
* you want to regularize a variable to a given value. The task represents the following equation
* \f[
* x = x_{des}
* \f]
* where \f$x\f$ are the elements of the variable you want to regularize to a given value.
*/
class VariableRegularizationTask : public TSIDLinearTask
{
std::string m_variableName; /**< Name of the variable considered that will be regularized */
std::vector<std::string> m_controlledElements; /**< Name of the variable elements considered in
the task */
bool m_isInitialized{false}; /**< True if the task has been initialized. */
bool m_isValid{false}; /**< True if the task is valid. */
std::size_t m_variableSize{0}; /**< Size of the regularized variable. */

public:
/**
* Initialize the planner.
* @param paramHandler pointer to the parameters handler.
* @param variablesHandler reference to a variables handler.
* @note the following parameters are required by the class
* | Parameter Name | Type | Description | Mandatory |
* |:----------------:|:--------:|:--------------------------------------------------------------------------------------:|:---------:|
* | `variable_name` | `string` | Name of the variable that you want to regularize | Yes |
* | `variable_size` | `int` | Number of the elements that will be regularized. | Yes |
* | `elements_name` | `vector` | Name of the elements to consider. If not specified all the elements are regularize to the desired vector | No |
* @return True in case of success, false otherwise.
*/
bool initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> paramHandler) override;

/**
* Set the set of variables required by the task. The variables are stored in the
* System::VariablesHandler.
* @param variablesHandler reference to a variables handler.
* @note The variablesHandler must contain a variable named as the parameter `variable_name`.
* @return True in case of success, false otherwise.
*/
bool setVariablesHandler(const System::VariablesHandler& variablesHandler) override;

/**
* Set the desired setpoint.
* @param setPoint vector containing the desired variable set point.
* @return True in case of success, false otherwise.
*/
bool setSetPoint(Eigen::Ref<const Eigen::VectorXd> setPoint);

/**
* Get the size of the task. (I.e the number of rows of the vector b)
* @return the size of the task.
*/
std::size_t size() const override;

/**
* The VariableRegularizationTask is an equality task.
* @return the type of the task.
*/
Type type() const override;

/**
* Determines the validity of the objects retrieved with getA() and getB()
* @return True if the objects are valid, false otherwise.
*/
bool isValid() const override;
};

} // namespace TSID
} // namespace BipedalLocomotion

#endif // BIPEDAL_LOCOMOTION_TSID_VARIABLE_REGULARIZATION_TASK_H
Loading

0 comments on commit 1e3a6fb

Please sign in to comment.