Commit 0ca806bc authored by Guilhem Saurel's avatar Guilhem Saurel
Browse files

Merge tag 'v3.6.0'

Release of version 3.6.0.
parents 7d1fbf60 655876f8
Pipeline #12039 failed with stage
in 9 minutes and 5 seconds
......@@ -25,6 +25,7 @@ SET(DOXYGEN_USE_MATHJAX YES)
# JRL-cmakemodule setup
INCLUDE(cmake/base.cmake)
INCLUDE(cmake/boost.cmake)
INCLUDE(cmake/lapack.cmake)
INCLUDE(cmake/python.cmake)
INCLUDE(cmake/sphinx.cmake)
......@@ -36,18 +37,18 @@ PROJECT(${PROJECT_NAME} ${PROJECT_ARGS})
ADD_PROJECT_DEPENDENCY(sot-tools REQUIRED PKG_CONFIG_REQUIRES sot-tools)
ADD_PROJECT_DEPENDENCY(example-robot-data)
SET(BOOST_COMPONENTS filesystem system unit_test_framework)
IF(BUILD_TESTING)
FIND_PACKAGE(Boost REQUIRED COMPONENTS unit_test_framework)
ENDIF(BUILD_TESTING)
IF(BUILD_PYTHON_INTERFACE)
FINDPYTHON()
SEARCH_FOR_BOOST_PYTHON(REQUIRED)
STRING(REGEX REPLACE "-" "_" PYTHON_DIR ${CUSTOM_HEADER_DIR})
ADD_PROJECT_DEPENDENCY(dynamic-graph-python REQUIRED
ADD_PROJECT_DEPENDENCY(dynamic-graph-python 4.0.0 REQUIRED
PKG_CONFIG_REQUIRES dynamic-graph-python)
SET(BOOST_COMPONENTS ${BOOST_COMPONENTS} python)
ENDIF(BUILD_PYTHON_INTERFACE)
SEARCH_FOR_BOOST()
# Main Library
SET(${PROJECT_NAME}_HEADERS
include/${CUSTOM_HEADER_DIR}/dynamic-pinocchio.h
......@@ -69,8 +70,7 @@ SET(${PROJECT_NAME}_SOURCES
ADD_LIBRARY(${PROJECT_NAME} SHARED
${${PROJECT_NAME}_SOURCES} ${${PROJECT_NAME}_HEADERS})
TARGET_INCLUDE_DIRECTORIES(${PROJECT_NAME} PUBLIC $<INSTALL_INTERFACE:include>)
TARGET_LINK_LIBRARIES(${PROJECT_NAME} ${Boost_LIBRARIES}
sot-core::sot-core)
TARGET_LINK_LIBRARIES(${PROJECT_NAME} sot-core::sot-core)
IF(SUFFIX_SO_VERSION)
SET_TARGET_PROPERTIES(${PROJECT_NAME} PROPERTIES SOVERSION ${PROJECT_VERSION})
......
......@@ -2,7 +2,7 @@ sot-dynamic-pinocchio
Encapsulate Pinocchio in SoT
===========
[![Building Status](https://travis-ci.org/stack-of-tasks/sot-dynamic-pinocchio.svg?branch=master)](https://travis-ci.org/stack-of-tasks/sot-dynamic-pinocchio)
[![License](https://img.shields.io/badge/License-BSD%202--Clause-green.svg)](https://opensource.org/licenses/BSD-2-Clause)
[![Pipeline status](https://gitlab.laas.fr/stack-of-tasks/sot-dynamic-pinocchio/badges/master/pipeline.svg)](https://gitlab.laas.fr/stack-of-tasks/sot-dynamic-pinocchio/commits/master)
[![Coverage report](https://gitlab.laas.fr/stack-of-tasks/sot-dynamic-pinocchio/badges/master/coverage.svg?job=doc-coverage)](http://projects.laas.fr/gepetto/doc/stack-of-tasks/sot-dynamic-pinocchio/master/coverage/)
......
Subproject commit 9e21ae2222fdb51dccd1320bb7208f73259b0c73
Subproject commit 9dcde03a880cccc86531019a6845708f5c54c35d
......@@ -5,6 +5,5 @@ IMAGE_PATH = @CMAKE_SOURCE_DIR@/doc/pictures
FILE_PATTERNS = *.cc *.cpp *.h *.hh *.hxx
TAGFILES = \
"@JRL_MAL_DOXYGENDOCDIR@/jrl-mal.doxytag = @JRL_MAL_DOXYGENDOCDIR@" \
"@DYNAMIC_GRAPH_DOXYGENDOCDIR@/dynamic-graph.doxytag = @DYNAMIC_GRAPH_DOXYGENDOCDIR@" \
"@SOT_CORE_DOXYGENDOCDIR@/sot-core.doxytag = @SOT_CORE_DOXYGENDOCDIR@"
......@@ -17,6 +17,7 @@
/* STD */
#include <string>
#include <map>
#include <memory>
/* SOT */
#include <pinocchio/fwd.hpp>
......@@ -29,6 +30,7 @@
#include <sot/core/matrix-geometry.hh>
/* Matrix */
#include <dynamic-graph/linear-algebra.h>
#include <sot/dynamic-pinocchio/deprecated.hh>
/* PINOCCHIO */
#include <pinocchio/macros.hpp>
......@@ -80,7 +82,7 @@ class SOTDYNAMIC_EXPORT DynamicPinocchio : public dg::Entity {
/* --- MODEL ATRIBUTES --- */
pinocchio::Model* m_model;
pinocchio::Data* m_data;
std::unique_ptr<pinocchio::Data> m_data;
/* --- MODEL ATRIBUTES --- */
......@@ -164,7 +166,15 @@ class SOTDYNAMIC_EXPORT DynamicPinocchio : public dg::Entity {
void setModel(pinocchio::Model*);
void setData(pinocchio::Data*);
void createData();
/// \deprecated this function does nothing. This class has its own
/// pinocchio::Data object, which can be access with \ref getData.
void setData(pinocchio::Data*) SOT_DYNAMIC_PINOCCHIO_DEPRECATED;
pinocchio::Model* getModel() { return m_model; };
pinocchio::Data* getData() { return m_data.get(); };
/* --- GETTERS --- */
......
<package format="2">
<name>sot-dynamic-pinocchio</name>
<version>3.5.2</version>
<version>3.6.0</version>
<description>
Pinocchio bindings for dynamic-graph
</description>
......
......@@ -18,7 +18,8 @@ SET(plugins
)
SET(integrator-force-rk4_plugins_deps integrator-force)
SET(integrator-force-exact_plugins_deps integrator-force)
SET(integrator-force-exact_plugins_deps integrator-force lapack)
SET(mass-apparent_plugins_deps integrator-force)
FOREACH(plugin ${plugins})
GET_FILENAME_COMPONENT(LIBRARY_NAME ${plugin} NAME)
......@@ -28,7 +29,8 @@ FOREACH(plugin ${plugins})
SET_TARGET_PROPERTIES(${LIBRARY_NAME} PROPERTIES SOVERSION ${PROJECT_VERSION})
ENDIF(SUFFIX_SO_VERSION)
TARGET_LINK_LIBRARIES(${LIBRARY_NAME} ${PROJECT_NAME} ${${LIBRARY_NAME}_deps})
TARGET_LINK_LIBRARIES(${LIBRARY_NAME}
PUBLIC ${PROJECT_NAME} ${${LIBRARY_NAME}_plugins_deps})
IF(NOT INSTALL_PYTHON_INTERFACE_ONLY)
INSTALL(TARGETS ${LIBRARY_NAME} EXPORT ${TARGETS_EXPORT_NAME}
......@@ -37,10 +39,15 @@ FOREACH(plugin ${plugins})
IF(BUILD_PYTHON_INTERFACE)
STRING(REPLACE - _ PYTHON_LIBRARY_NAME ${LIBRARY_NAME})
DYNAMIC_GRAPH_PYTHON_MODULE("${PYTHON_DIR}/${PYTHON_LIBRARY_NAME}"
${LIBRARY_NAME} ${PROJECT_NAME}-${PYTHON_LIBRARY_NAME}-wrap
1 "src/python-module-py.cpp")
TARGET_LINK_BOOST_PYTHON(${PROJECT_NAME}-${PYTHON_LIBRARY_NAME}-wrap)
if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/${plugin}-python-module-py.cc")
DYNAMIC_GRAPH_PYTHON_MODULE("${PYTHON_DIR}/${PYTHON_LIBRARY_NAME}"
${LIBRARY_NAME} ${PROJECT_NAME}-${PYTHON_LIBRARY_NAME}-wrap
SOURCE_PYTHON_MODULE "${CMAKE_CURRENT_SOURCE_DIR}/${plugin}-python-module-py.cc")
elseif(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/${plugin}-python.hh")
DYNAMIC_GRAPH_PYTHON_MODULE("${PYTHON_DIR}/${PYTHON_LIBRARY_NAME}"
${LIBRARY_NAME} ${PROJECT_NAME}-${PYTHON_LIBRARY_NAME}-wrap
MODULE_HEADER "${CMAKE_CURRENT_SOURCE_DIR}/${plugin}-python.hh")
endif()
ENDIF(BUILD_PYTHON_INTERFACE)
ENDFOREACH(plugin)
......
#include <sot/dynamic-pinocchio/angle-estimator.h>
typedef boost::mpl::vector< dynamicgraph::sot::AngleEstimator > entities_t;
......@@ -75,8 +75,7 @@ class GetJointNames : public Command {
}
const std::vector<std::string>& jointNames = robot.m_model->names;
// Remove first joint names 'universe'
std::size_t n(jointNames.size());
assert(n >= 1);
assert(jointNames.size() >= 1);
std::vector<Value> res;
for (std::size_t i = 1; i < jointNames.size(); ++i) {
res.push_back(Value(jointNames[i]));
......
#include <dynamic-graph/python/module.hh>
#include <sot/dynamic-pinocchio/dynamic-pinocchio.h>
namespace dg = dynamicgraph;
namespace dgs = dynamicgraph::sot;
typedef bp::return_value_policy<bp::reference_existing_object> reference_existing_object;
BOOST_PYTHON_MODULE(wrap)
{
bp::import("dynamic_graph");
bp::import("pinocchio");
dg::python::exposeEntity<dgs::DynamicPinocchio, bp::bases<dg::Entity>, dg::python::AddCommands>()
.add_property("model",
bp::make_function(&dgs::DynamicPinocchio::getModel, reference_existing_object()),
bp::make_function(&dgs::DynamicPinocchio::setModel))
.add_property("data",
bp::make_function(&dgs::DynamicPinocchio::getData, reference_existing_object()),
bp::make_function(&dgs::DynamicPinocchio::setData))
.def("setModel", &dgs::DynamicPinocchio::setModel)
.def("createData", &dgs::DynamicPinocchio::createData)
.def("setData", &dgs::DynamicPinocchio::setData)
;
}
import numpy as np
from numpy import cos, sin, sqrt
from .dynamic import DynamicPinocchio as DynamicCpp
# DynamicOld = Dynamic
class DynamicPinocchio(DynamicCpp):
def __init__(self, name):
DynamicCpp.__init__(self, name)
self.model = None
self.data = None
def setData(self, pinocchio_data):
dynamic.wrap.set_pinocchio_data(self.obj, pinocchio_data) # noqa TODO
self.data = pinocchio_data
return
def setModel(self, pinocchio_model):
dynamic.wrap.set_pinocchio_model(self.obj, pinocchio_model) # noqa TODO
self.model = pinocchio_model
return
from .dynamic import DynamicPinocchio
def fromSotToPinocchio(q_sot, freeflyer=True):
if freeflyer:
......
......@@ -271,9 +271,12 @@ class AbstractRobot(ABC):
"""
Half sitting configuration.
"""
self.halfSitting = numpy.asarray(pinocchio.neutral(self.pinocchioModel)).flatten().tolist()
self.halfSitting = pinocchio.neutral(self.pinocchioModel)
self.defineHalfSitting(self.halfSitting)
self.halfSitting[3:7] = [0., 0., 0.] # Replace quaternion by RPY.
self.halfSitting = numpy.array(self.halfSitting[:3].tolist()
+ [0., 0., 0.] # Replace quaternion by RPY.
+ self.halfSitting[7:].tolist())
assert self.halfSitting.shape[0] == self.dynamic.getDimension()
# Set the device limits.
def get(s):
......@@ -283,9 +286,10 @@ class AbstractRobot(ABC):
def opposite(v):
return [-x for x in v]
self.device.setPositionBounds(get(self.dynamic.lowerJl), get(self.dynamic.upperJl))
self.device.setVelocityBounds(opposite(get(self.dynamic.upperVl)), get(self.dynamic.upperVl))
self.device.setTorqueBounds(opposite(get(self.dynamic.upperTl)), get(self.dynamic.upperTl))
self.dynamic.add_signals()
self.device.setPositionBounds( get(self.dynamic.lowerJl), get(self.dynamic.upperJl))
self.device.setVelocityBounds(-get(self.dynamic.upperVl), get(self.dynamic.upperVl))
self.device.setTorqueBounds (-get(self.dynamic.upperTl), get(self.dynamic.upperTl))
# Freeflyer reference frame should be the same as global
# frame so that operational point positions correspond to
......@@ -299,7 +303,7 @@ class AbstractRobot(ABC):
plug(self.device.state, self.velocityDerivator.sin)
plug(self.velocityDerivator.sout, self.dynamic.velocity)
else:
self.dynamic.velocity.value = self.dimension * (0., )
self.dynamic.velocity.value = numpy.zeros([self.dimension,])
if self.enableAccelerationDerivator:
self.accelerationDerivator = \
......@@ -308,7 +312,7 @@ class AbstractRobot(ABC):
plug(self.velocityDerivator.sout, self.accelerationDerivator.sin)
plug(self.accelerationDerivator.sout, self.dynamic.acceleration)
else:
self.dynamic.acceleration.value = self.dimension * (0., )
self.dynamic.acceleration.value = numpy.zeros([self.dimension,])
def addTrace(self, entityName, signalName):
if self.tracer:
......
#include <sot/dynamic-pinocchio/integrator-force-exact.h>
typedef boost::mpl::vector< dynamicgraph::sot::IntegratorForceExact > entities_t;
#include <sot/dynamic-pinocchio/integrator-force.h>
typedef boost::mpl::vector< dynamicgraph::sot::IntegratorForce > entities_t;
#include <sot/dynamic-pinocchio/integrator-force-rk4.h>
typedef boost::mpl::vector< dynamicgraph::sot::IntegratorForceRK4 > entities_t;
#include <sot/dynamic-pinocchio/mass-apparent.h>
typedef boost::mpl::vector< dynamicgraph::sot::MassApparent > entities_t;
// Copyright (C) 2008-2016, 2019 LAAS-CNRS, JRL AIST-CNRS.
#define PY_SSIZE_T_CLEAN
#include <sot/core/debug.hh>
#include <sot/dynamic-pinocchio/dynamic-pinocchio.h>
#include <Python.h>
#include <boost/python.hpp>
#include <typeinfo>
#include <cstdio>
namespace dynamicgraph {
namespace sot {
PyObject* setPinocchioModel(PyObject* /* self */, PyObject* args) {
PyObject* object = NULL;
PyObject* pyPinocchioObject;
void* pointer1 = NULL;
pinocchio::Model* pointer2 = NULL;
if (!PyArg_ParseTuple(args, "OO", &object, &pyPinocchioObject)) return NULL;
if (!PyCapsule_CheckExact(object)) {
PyErr_SetString(PyExc_TypeError, "function takes a PyCapsule as argument");
return NULL;
}
pointer1 = PyCapsule_GetPointer(object, "dynamic_graph.Entity");
DynamicPinocchio* dyn_entity = (DynamicPinocchio*)pointer1;
try {
boost::python::extract<pinocchio::Model&> cppHandle(pyPinocchioObject);
pointer2 = (pinocchio::Model*)&cppHandle();
dyn_entity->setModel(pointer2);
} catch (const std::exception& exc) {
// PyErr_SetString(dgpyError, exc.what());
return NULL;
} catch (const char* s) {
// PyErr_SetString(dgpyError, s);
return NULL;
} catch (...) {
// PyErr_SetString(dgpyError, "Unknown exception");
return NULL;
}
return Py_BuildValue("");
}
PyObject* setPinocchioData(PyObject* /* self */, PyObject* args) {
PyObject* object = NULL;
PyObject* pyPinocchioObject;
void* pointer1 = NULL;
pinocchio::Data* pointer2 = NULL;
if (!PyArg_ParseTuple(args, "OO", &object, &pyPinocchioObject)) return NULL;
if (!PyCapsule_CheckExact(object)) {
PyErr_SetString(PyExc_TypeError, "function takes a PyCapsule as argument");
return NULL;
}
pointer1 = PyCapsule_GetPointer(object, "dynamic_graph.Entity");
DynamicPinocchio* dyn_entity = (DynamicPinocchio*)pointer1;
try {
boost::python::extract<pinocchio::Data&> cppHandle(pyPinocchioObject);
pointer2 = (pinocchio::Data*)&cppHandle();
dyn_entity->setData(pointer2);
} catch (const std::exception& exc) {
// PyErr_SetString(dgpyError, exc.what());
return NULL;
} catch (const char* s) {
// PyErr_SetString(dgpyError, s);
return NULL;
} catch (...) {
// PyErr_SetString(dgpyError, "Unknown exception");
return NULL;
}
return Py_BuildValue("");
}
} // namespace sot
} // namespace dynamicgraph
/**
\brief List of python functions
*/
static PyMethodDef functions[] = {
/* {"get_pinocchio_model", dynamicgraph::sot::getPinocchioModel, METH_VARARGS,
"Get the pinocchio model as python object"},*/
{"set_pinocchio_model", dynamicgraph::sot::setPinocchioModel, METH_VARARGS,
"Set the model from pinocchio python object"},
{"set_pinocchio_data", dynamicgraph::sot::setPinocchioData, METH_VARARGS,
"Set the data from pinocchio python object"},
{NULL, NULL, 0, NULL} /* Sentinel */
};
#if PY_MAJOR_VERSION >= 3
static struct PyModuleDef SotDynamicPinocchioModuleDef = {
PyModuleDef_HEAD_INIT, "wrap", NULL, 0, functions, NULL, NULL, NULL, NULL};
#define INITERROR return NULL
#else
#define INITERROR return
#endif
#ifdef __cplusplus
extern "C" {
#endif
#if PY_MAJOR_VERSION >= 3
PyMODINIT_FUNC PyInit_wrap(void)
#else
void initwrap(void)
#endif
{
#if PY_MAJOR_VERSION >= 3
PyObject* module = PyModule_Create(&SotDynamicPinocchioModuleDef);
#else
PyObject* module = Py_InitModule("wrap", functions);
#endif
if (module == NULL) INITERROR;
#if PY_MAJOR_VERSION >= 3
return module;
#endif
}
#ifdef __cplusplus
} // extern "C"
#endif
......@@ -35,7 +35,7 @@ const std::string dg::sot::DynamicPinocchio::CLASS_NAME = "DynamicPinocchio";
DynamicPinocchio::DynamicPinocchio(const std::string& name)
: Entity(name),
m_model(NULL),
m_data(NULL)
m_data()
,
jointPositionSIN(NULL, "sotDynamicPinocchio(" + name + ")::input(vector)::position"),
......@@ -241,9 +241,15 @@ void DynamicPinocchio::setModel(pinocchio::Model* modelPtr) {
if (pinocchio::nq(this->m_model->joints[i]) == 4) // Spherical Joint Only
sphericalJoints.push_back(pinocchio::idx_v(this->m_model->joints[i]));
}
createData();
}
void DynamicPinocchio::setData(pinocchio::Data* dataPtr) { this->m_data = dataPtr; }
void DynamicPinocchio::setData(pinocchio::Data*) {}
void DynamicPinocchio::createData() {
m_data.reset(new pinocchio::Data (*m_model));
}
/*--------------------------------GETTERS-------------------------------------------*/
......@@ -713,8 +719,16 @@ dg::Matrix& DynamicPinocchio::computeGenericEndeffJacobian(const bool isFrame, c
jid = frame.parent;
M = frame.placement.inverse();
if (!isLocal) // Express the jacobian is world coordinate system.
M.rotation() = m_data->oMf[fid].rotation() * M.rotation();
if (!isLocal) {// Express the jacobian is world coordinate system.
// Need to compute frame placement for oMf.
pinocchio::updateFramePlacement(*m_model, *m_data, fid);
pinocchio::SE3 T;
T.rotation() = m_data->oMf[fid].rotation();
T.translation().setZero();
M = T * M;
}
} else {
jid = (pinocchio::JointIndex)id;
if (!isLocal) { // Express the jacobian is world coordinate system.
......
#include <sot/dynamic-pinocchio/waist-attitude-from-sensor.h>
typedef boost::mpl::vector< dynamicgraph::sot::WaistAttitudeFromSensor > entities_t;
#include "zmp-from-forces.h"
typedef boost::mpl::vector< sot::dynamic::ZmpFromForces > entities_t;
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment