Git Product home page Git Product logo

tsid's Introduction

TSID - Task Space Inverse Dynamics

License Pipeline status Coverage report PyPI version Code style: black

TSID is a C++ library for optimization-based inverse-dynamics control based on the rigid multi-body dynamics library Pinocchio.

Documentation

  • Take a look at the project wiki for an overview of the design of the library.
  • In the exercises folder you can find several examples of how to use TSID in Python with robot manipulators, humanoids, or quadrupeds.
  • On the website of Andrea Del Prete you can find slides and video lessons on TSID.
  • Memmo 2020 summer school

Installation with Conda

If you want to directly dive into TSID in Python, only one single line is sufficient (assuming you have Conda installed):

conda install tsid -c conda-forge

Installation from Debian/Ubuntu packages, with robotpkg

If you have never added robotpkg's software repository you can do it with the following commands:

sudo tee /etc/apt/sources.list.d/robotpkg.list <<EOF
deb [arch=amd64] http://robotpkg.openrobots.org/packages/debian/pub $(lsb_release -sc) robotpkg
EOF

curl http://robotpkg.openrobots.org/packages/debian/robotpkg.key | sudo apt-key add -
sudo apt update

You can install TSID and its python bindings (replace * with you Python version) with:

sudo apt install robotpkg-py3*-tsid

Installation from sources

First you need to install the following dependencies:

To install eigen3 on Ubuntu you can use apt-get: sudo apt-get install libeigen3-dev

To install pinocchio follow the instruction on its website.

To compile TSID:

cd $DEVEL/openrobots/src/
git clone --recursive [email protected]:stack-of-tasks/tsid.git
cd tsid
mkdir _build-RELEASE
cd _build-RELEASE
cmake .. -DCMAKE_BUILD_TYPE=RELEASE -DCMAKE_INSTALL_PREFIX=$DEVEL/openrobots
make install

Python Bindings

To use this library in python, we offer python bindings based on Boost.Python and EigenPy.

To install EigenPy you can compile the source code:

git clone https://github.com/stack-of-tasks/eigenpy

or, on Ubuntu, you can use apt-get:

sudo apt-get install robotpkg-py3*-eigenpy

For testing the python bindings, you can run the unit test scripts in the script folder, for instance:

ipython script/test_formulation.py

To run the demo using gepetto-viewer:

ipython demo/demo_romeo.py

Credits

This package is authored by:

It includes key contributions from:

And is maintained by:

Citing

If you are (or not) happy with TSID and want to cite it, please use the following citation:

@inproceedings {adelprete:jnrh:2016,
    title = {Implementing Torque Control with High-Ratio Gear Boxes and without Joint-Torque Sensors},
    booktitle = {Int. Journal of Humanoid Robotics},
    year = {2016},
    pages = {1550044},
    url = {https://hal.archives-ouvertes.fr/hal-01136936/document},
    author = {Andrea Del Prete, Nicolas Mansard, Oscar E Ramos, Olivier Stasse, Francesco Nori}
}

tsid's People

Contributors

abonnefoy avatar andreadelprete avatar dalinel avatar egordv avatar etiennear avatar fabinsch avatar flforget avatar francois-keith avatar ggory15 avatar groulaxx avatar ibergonzani avatar jbmouret avatar jcarpent avatar jmirabel avatar jviereck avatar nim65s avatar noelieramuzat avatar olivier-stasse avatar paleziart avatar paulinejmaurice avatar pfernbach avatar pre-commit-ci[bot] avatar proyan avatar rascof avatar shr-project avatar thomasfla avatar wxmerkt avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

tsid's Issues

Problem referencing Pinocchio

Hi guys,

I'm trying to follow your installation instructions and I'm getting the following error:

image

Any ideas what can be wrong?

Thanks,
Misha.

Python bindings, segmentation fault, InverseDynamicsFormulationAccForce.data()

Since updating to the latest version of pinocchio (branch devel, commit 2a8bd3d711e43ca449c3a75c9f3468e2b17ae4fc) I get a segmentation fault when in Python (3.5) I call the method data() of the class InverseDynamicsFormulationAccForce. I am on Ubuntu 16.04 and I am using the devel branch of TSID.

All the other methods seem to work fine, indeed I can execute the script exercizes/ex_0_ur5_joint_space_control.py without any problem.

I wonder whether somebody is aware of any recent change in the Python bindings of pinocchio, especially the Data class, which could explain this error.

This is a minimal working example to reproduce the problem:

import pinocchio as se3
import tsid
import os

ERROR_MSG = 'You should set the environment variable UR5_MODEL_DIR to something like "$DEVEL_DIR/install/share"\n';
path      = os.environ.get('UR5_MODEL_DIR', ERROR_MSG)
urdf      = path + "/ur_description/urdf/ur5_robot.urdf";
srdf      = path + '/ur_description/srdf/ur5_robot.srdf'

vector = se3.StdVec_StdString()
vector.extend(item for item in path)
robot = tsid.RobotWrapper(urdf, vector, False)
formulation = tsid.InverseDynamicsFormulationAccForce("tsid", robot, False)
formulation.data()
print("Still alive")

Wrong convergence of the contact force reference

@paLeziart repported a wrong convergence of the contact forces when a reference is given.

The contact force equality task seems to be miss-formulated :

m_forceRegTask.setVector(m_fRef);

I think m_forceRegTask.setVector(m_fRef); should be replaced by m_forceRegTask.setVector(m_fRef * m_weightForceRegTask);

Same applies

m_forceRegTask.setVector(m_fRef);

new feature : convex hull constraint

Hi,

I want to implement a convex hull constraint (inequality constraint) in TSID.

I got some code that works well in Inverse Kinematics.

So first, let me introduce the goal of this constraint. The idea is to perform a cartesian constraint on x and y plan directly on the Center of Mass based on the support polygons of the current feet state.

It defines a set of contact point which define the support polygon, and then it calculates the different line coefficient () with CoM like reference frame.
With these coefficients, it's easy to compute something in IK like :

For example with 4 points for the support polygon, I obtained :
with A [4x2] ( and coef), b=[4x1] ( coef) and J_com is [2xDoF] (x and y components).

So now, I would like to extend this in Inverse Dynamics. From my guess, I just used the same equation but expressed with the acceleration :


So far, I tried to implement that, but it stills not working efficiently. I mean the robot stills go out of its convex hull.
Could you tell me if this current formulation is OK or completely wrong/miss something?

Organization

Dear Justin,
Would it possible to move or to make an official repository on the stack-of-tasks organization ?
sot-torque-controller depends on your package...

Best Regards,
Olivier.

self collision avoidance

Hi,
Do you have any ideas or tips about how to implement self collision avoidance for tsid ?
Thank you in advance

Missing includes

Hi,

This library does not compile with pinocchio v1.3.1:

include/tsid/robots/robot-wrapper.hpp:113:32 : error: 'se3::Data::Matrix6x' has not been declared

Installation problem with pinocchio dependency

I followed Pinocchio's installation procedure and installed it on Ubuntu 16.04. Then, I followed the tsid's installation guide. However, ADD_REQUIRED_DEPENDENCY("pinocchio >= 1.3.0") in CMakeLists.txt does not seem to be satisfied.

After cmake .. -DCMAKE_BUILD_TYPE=RELEASE -DCMAKE_INSTALL_PREFIX=$DEVEL/openrobots, I got the following error message.

-- Option EIGEN_RUNTIME_NO_MALLOC on.
-- eigen3 >= 3.2.0 is required.
-- Checking for module 'eigen3 >= 3.2.0'
--   Found eigen3 , version 3.2.92
-- Pkg-config module eigen3 v3.2.92 has been detected with success.
-- pinocchio >= 1.3.0 is required.
-- Checking for module 'pinocchio >= 1.3.0'
--   
CMake Error at /usr/share/cmake-3.5/Modules/FindPkgConfig.cmake:367 (message):
  A required package was not found
Call Stack (most recent call first):
  /usr/share/cmake-3.5/Modules/FindPkgConfig.cmake:532 (_pkg_check_modules_internal)
  cmake/pkg-config.cmake:288 (PKG_CHECK_MODULES)
  cmake/pkg-config.cmake:459 (ADD_DEPENDENCY)
  CMakeLists.txt:76 (ADD_REQUIRED_DEPENDENCY)


-- Configuring incomplete, errors occurred!
See also "/opt/openrobots/src/tsid/_build-RELEASE/CMakeFiles/CMakeOutput.log".

apt list --installed | grep pinocchio gave me

robotpkg-pinocchio/xenial,now 1.3.3 amd64 [installed,automatic]
robotpkg-py27-pinocchio/xenial,now 1.3.3 amd64 [installed]

Any help would be appreciated.

angular-momentum-equality task is not using ref.pos

The task-angular-momentum-equality take the reference momentum from the trajectorySample.vel() value (https://github.com/stack-of-tasks/tsid/blob/master/src/tasks/task-angular-momentum-equality.cpp#L98) and it's derivative from the trajectorySample.acc() value (https://github.com/stack-of-tasks/tsid/blob/master/src/tasks/task-angular-momentum-equality.cpp#L103).

I think that I understand the reasoning here that a momentum is relative to a 'velocity'. But as the name of the task suggest I would have expected to set the momentum reference from the trajectorySample.pos() value and it's derivative from the trajectorySample.vel() value.

Can I propose a PR to change this or should we keep the current behaviour ?

Generalize RobotWrapper.position and RobotWrapper.framePosition

Most of the demo/exercizes are writted assuming the "feet names" represent joints in the pinocchio model (see eg. https://github.com/stack-of-tasks/tsid/blob/master/demo/demo_romeo.py#L89, also the name in this script are misleading rf_frame_name is the name of a joint in the pinocchio model). However it is not always true, like for Talos where the feet are represented by frames.

This may cause confusion or create hard to find issue when using this scripts and changing robot model because the call to robot.position(data, robot.model().getJointId(ee_name)) still execute without error even if ee_name is the name of a frame, but in this case it return garbage.

I had to add the following method in my code to be able to deal with the fact that ee_name could be a joint or a frame:

def get_current_effector_position(robot, data, ee_name):
    id = robot.model().getJointId(ee_name)
    if id < len(data.oMi):
        return robot.position(data, id)
    else:
        id = robot.model().getFrameId(ee_name)
        return robot.framePosition(data, id)

I do not know what is your policy for checking user inputs when calling RobotWrapper methods, but I think that RobotWrapper.position() should check that the id is valid. (Either with an assert, warning message or throw an error as you prefer).

Release & Pinocchio v2

Hi @andreadelprete

Following discussions in stack-of-tasks/pinocchio#645 I would like to know what is the current status of this package.
Is it ready for a new release, or are you still working on it ?
I can make the release if you want, adressing #20 in the same time.

And is the pinocchio_v2 branch ready ? If so I could also merge it for the release, and publish it to robotpkg at the same moment as every other of our projects that depend on hpp-fcl / pinocchio.

Externalize QP solver

This issue is to keep track of our discussion and let others know.

It would be interesting to create a repository containing the LP and QP solvers API developed in different packages. Some people (at least, me) would take advantage of such a repo. From the discussion with @andreadelprete , it seems there is not too much work to be done.

Frames handling for task-se3-equality

Dear all,

Recently I checked the code of the task-se3-equality that I am using for feet in swing phase and I want to be sure I am not misunderstanding something.

In the compute function of task-se3-equality (https://github.com/stack-of-tasks/tsid/blob/devel/src/tasks/task-se3-equality.cpp#L164), you first create a SE3 object called oMi that you initialize with m_robot.framePosition(data, m_frame_id, oMi);.

In the function framePosition (https://github.com/stack-of-tasks/tsid/blob/devel/src/robots/robot-wrapper.cpp#L207), the placement of the frame is retrieved like that framePosition = data.oMi[f.parent].act(f.placement); with data.oMi[f.parent] being the vector of absolute joint placements (wrt the world) according to Pinocchio documentation and f.placement being the placement of the frame wrt the parent joint. So from what I understand and with the numerical values I've read framePosition contains the current placement of the foot frame wrt the world.

The desired placement of the foot frame is set with the setReference function (https://github.com/stack-of-tasks/tsid/blob/devel/src/tasks/task-se3-equality.cpp#L96) with vectorToSE3(ref.pos, m_M_ref);. I'm setting this desired placement wrt world frame.

The error in position for the task is then errorInSE3(oMi, m_M_ref, m_p_error); // pos err in local frame with the errorInSE3 function doing error = pinocchio::log6(Mdes.inverse() * M);. Since both the current and desired placements are in world frame, this error is too.

So in the rest of the compute function if we are working in local frame (m_local_frame = True) then this position error is directly mixed with other quantities expressed in the local frame of the foot.

 // desired acc in local frame
 m_a_des = - m_Kp.cwiseProduct(m_p_error_vec)
                  - m_Kd.cwiseProduct(m_v_error.toVector())
                  + m_wMl.actInv(m_a_ref).toVector();

And if we are not working in local frame (m_local_frame = False) this position error is transformed from local to world frame before being used, except it is already in world frame.
m_p_error_vec = m_wMl.toActionMatrix() * m_p_error.toVector(); // pos err in local world-oriented frame

Could you tell me if I misunderstood something? Maybe the reference position of the foot should be given in its local frame? Thanks a lot!

Best regards,

devel stalled

Dear all,
The devel branch is stalled and behind master.
I suggest to remove the devel branch if this is fine with everyone.

Improve computation time of HQP solver

Currently the only QP solver implemented is eiquadprog, which is already rather efficient, but there's room for improvement. In particular, the current version of the solver allocates dynamic memory at each call to the solver, so it should be easy to decrease computation time by pre-allocating all the necessary memory in an initialization phase.

error ‘parseURDFFile’ is not a member of ‘urdf’

Last week I have installed pinocchio through sudo apt install robotpkg-py27-pinocchio and now I want to install TSID.
I have followed the guide and when I try to install with make install, I get the following error when it is creating the robot-wrapper.cpp.o

cd /opt/openrobots/src/tsid/_build-RELEASE/src && /usr/lib/ccache/c++   -DEIGEN_RUNTIME_NO_MALLOC -DROS_BUILD_SHARED_LIBS=1 -Dtsid_EXPORTS -I/opt/openrobots/src/tsid/_build-RELEASE -I/opt/openrobots/src/tsid/_build-RELEASE/include -I/opt/openrobots/src/tsid/include -isystem /usr/include/python2.7 -isystem /usr/include/eigen3 -isystem /opt/openrobots/include -isystem /usr/include/assimp  -pedantic -Wno-long-long -Wall -Wextra -Wcast-align -Wcast-qual -Wformat -Wwrite-strings -Wconversion  -O3 -DNDEBUG -fPIC   -DPINOCCHIO_URDFDOM_TYPEDEF_SHARED_PTR -DBOOST_MPL_LIMIT_LIST_SIZE=30 -DPINOCCHIO_WITH_URDFDOM -DPINOCCHIO_WITH_HPP_FCL -DFCL_USE_ASSIMP_UNIFIED_HEADER_NAMES -DHPP_FCL_USE_ASSIMP_UNIFIED_HEADER_NAMES -DHPP_FCL_HAVE_OCTOMAP -DFCL_HAVE_OCTOMAP -DOCTOMAP_MAJOR_VERSION=1 -DOCTOMAP_MINOR_VERSION=9 -DOCTOMAP_PATCH_VERSION=0 -o CMakeFiles/tsid.dir/robots/robot-wrapper.cpp.o -c /opt/openrobots/src/tsid/src/robots/robot-wrapper.cpp
In file included from /opt/openrobots/include/pinocchio/parsers/urdf.hpp:263:0,
                 from /opt/openrobots/src/tsid/src/robots/robot-wrapper.cpp:21:
/opt/openrobots/include/pinocchio/parsers/urdf/model.hxx: In function ‘pinocchio::ModelTpl<Scalar, Options, JointCollectionTpl>& pinocchio::urdf::buildModel(const string&, const typename pinocchio::ModelTpl<Scalar, Options, JointCollectionTpl>::JointModel&, pinocchio::ModelTpl<Scalar, Options, JointCollectionTpl>&, bool)’:
/opt/openrobots/include/pinocchio/parsers/urdf/model.hxx:618:50: error: ‘parseURDFFile’ is not a member of ‘urdf’
       ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile (filename);
                                                  ^
/opt/openrobots/include/pinocchio/parsers/urdf/model.hxx: In function ‘pinocchio::ModelTpl<Scalar, Options, JointCollectionTpl>& pinocchio::urdf::buildModel(const string&, pinocchio::ModelTpl<Scalar, Options, JointCollectionTpl>&, bool)’:
/opt/openrobots/include/pinocchio/parsers/urdf/model.hxx:638:50: error: ‘parseURDFFile’ is not a member of ‘urdf’
       ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile(filename);
                                                  ^
src/CMakeFiles/tsid.dir/build.make:785: recipe for target 'src/CMakeFiles/tsid.dir/robots/robot-wrapper.cpp.o' failed

How can I fix this?
Thanks

Change gravity

Hey,
I would like to change the gravity in TSID, to turn it to 0.
In Pinocchio, I would do that with model.gravity = pinocchio.Motion.Zero(). Yet I don't have a direct access to the pinocchio model in the TSID robot wrapper (robot.model() gives me access, I believe, to a copy of the pinocchio model).

What do you think is the best way to change the gravity in TSID? Should I add a setter function in TSID, e.g. setGravity(const Motion & g), and wrap it in python?

Thanks for your advices.

Implement Python bindings

To easily exploit the library features and to have a common framework for all the Gepetto team, Python bindings must be implemented.

"print" in function solve

Since the last package update, when doing

solver = tsid.SolverHQuadProgFast("qp solver")
solver.resize(invdyn.nVar, invdyn.nEq, invdyn.nIn) 
sol = solver.solve(HQPData)

a lot of data are printed, like for example

Unconstrained solution: -1.01038
Add constraint 0/1
Add constraint 1/2
Add constraint 2/3
Add constraint 3/4
Add constraint 4/5
Add constraint 5/6
Add constraint 6/7
Add constraint 7/8
Add constraint 8/9
Add constraint 9/10
Add constraint 10/11
Add constraint 11/12
Add constraint 12/13
Add constraint 13/14
Add constraint 14/15
Trying with constraint 6
Step direction z
Step sizes: 2.87851e-05 (t1 = inf, t2 = 2.87851e-05)  in both spaces: 0.000121391
Full step has taken 2.87851e-05
Add constraint 15/16
Trying with constraint 7
Step direction z
Step sizes: 1.53276e-05 (t1 = 7.59971e-05, t2 = 1.53276e-05)  in both spaces: 0.000126826
Full step has taken 1.53276e-05
Add constraint 16/17

It spams a lot, is there any way to

  • either do the printing in a separate function (like HQPData.print_all() for example)
  • either adding an argument to remove the printing

Thanks

Running demo_quadruped.py gives malloc error

The current version of the demo_quadruped.py uses the tsid.SolverHQuadProgFast, which under debug mode yields a not allowed malloc error. When changing to tsid.SolverHQuadProg, this error goes away (though there is a new one due to reading of the contact force in the 3d PointContact case from invdyn.getContactForce(contact.name, sol) - that's a separate bug I look into tomorrow):

$ gdb -ex r --args python demo_quadruped.py

[...]

[SolverHQuadProgFast.qp solver] Resizing equality constraints from 0 to 18
[SolverHQuadProgFast.qp solver] Resizing inequality constraints from 0 to 20
[SolverHQuadProgFast.qp solver] Resizing Hessian from 0 to 26
Level 0
 - base-dynamics: w=1, equality, 6x26
 - BL_contact_force_constraint: w=1, inequality, 5x26
 - BR_contact_force_constraint: w=1, inequality, 5x26
 - FL_contact_force_constraint: w=1, inequality, 5x26
 - FR_contact_force_constraint: w=1, inequality, 5x26
Level 1
 - BL_contact_motion_task: w=1, equality, 3x26
 - BL_contact_force_reg_task: w=1e-05, equality, 3x26
 - BR_contact_motion_task: w=1, equality, 3x26
 - BR_contact_force_reg_task: w=1e-05, equality, 3x26
 - FL_contact_motion_task: w=1, equality, 3x26
 - FL_contact_force_reg_task: w=1e-05, equality, 3x26
 - FR_contact_motion_task: w=1, equality, 3x26
 - FR_contact_force_reg_task: w=1e-05, equality, 3x26
 - task-com: w=1, equality, 3x26
 - task-posture: w=0.001, equality, 8x26

[SolverHQuadProgFast.qp solver] Resizing equality constraints from 18 to 6
python: /usr/include/eigen3/Eigen/src/Core/util/Memory.h:206: void 
Eigen::internal::check_that_malloc_is_allowed(): Assertion `is_malloc_allowed() && "heap allocation is 
forbidden (EIGEN_RUNTIME_NO_MALLOC is defined and g_is_malloc_allowed is false)"' failed.

[...]

#10 0x00007fffc82dab26 in tsid::solvers::SolverHQuadProgFast::resize (this=0x1bb0cf0, n=26, neq=6, nin=20)
    at /home/jviereck/dev/tools/tsid/src/solvers/solver-HQP-eiquadprog-fast.cpp:58
58	        m_CE.resize(neq, n);

definitions not included in header file

The definitions of tsid::solvers::SolverHQuadProgRT are in the hxx file, which are not included when one includes the hpp header. So at runtime, since the symbols are not defined, there is an undefined symbol error.

I tried to include <tsid/solvers/solver-HQP-eiquadprog-rt.hxx> in addition to the hpp file, and it gives me the following error:
<INSTALL>/include/tsid/solvers/solver-HQP-eiquadprog-rt.hxx:149:11: error: ‘set_is_malloc_allowed’ is not a member of ‘Eigen::internal’ EIGEN_MALLOC_ALLOWED ^ <INSTALL>/include/tsid/solvers/solver-HQP-eiquadprog-rt.hxx:151:11: error: ‘set_is_malloc_allowed’ is not a member of ‘Eigen::internal’ EIGEN_MALLOC_NOT_ALLOWED ^ <INSTALL>/include/tsid/solvers/solver-HQP-eiquadprog-rt.hxx:175:7: error: ‘set_is_malloc_allowed’ is not a member of ‘Eigen::internal’ EIGEN_MALLOC_ALLOWED

And I can't find the macros EIGEN_MALLOC(_NOT)_ALLOWED in the eigen header directory
Any clues on how to solve this?

signature C++ problem with python bindings

With robotpkg install and pinocchio 2.1.7 when trying to do

cd exercizes
python ex_1.py

I have the following error:

Traceback (most recent call last):
  File "ex_1.py", line 15, in <module>
    tsid = TsidBiped(conf)
  File "/home/ostasse/devel-src/SoT/tsid/exercizes/tsid_biped.py", line 24, in __init__
    self.robot = tsid.RobotWrapper(conf.urdf, vector, pin.JointModelFreeFlyer(), False)
Boost.Python.ArgumentError: Python argument types in
    RobotWrapper.__init__(RobotWrapper, str, StdVec_StdString, JointModelFreeFlyer, bool)
did not match C++ signature:
    __init__(_object*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > filename, std::vector<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, std::allocator<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > > > package_dir, boost::variant<pinocchio::JointModelRevoluteTpl<double, 0, 0>, pinocchio::JointModelRevoluteTpl<double, 0, 1>, pinocchio::JointModelRevoluteTpl<double, 0, 2>, pinocchio::JointModelMimic<pinocchio::JointModelRevoluteTpl<double, 0, 0> >, pinocchio::JointModelMimic<pinocchio::JointModelRevoluteTpl<double, 0, 1> >, pinocchio::JointModelMimic<pinocchio::JointModelRevoluteTpl<double, 0, 2> >, pinocchio::JointModelFreeFlyerTpl<double, 0>, pinocchio::JointModelPlanarTpl<double, 0>, pinocchio::JointModelRevoluteUnalignedTpl<double, 0>, pinocchio::JointModelSphericalTpl<double, 0>, pinocchio::JointModelSphericalZYXTpl<double, 0>, pinocchio::JointModelPrismaticTpl<double, 0, 0>, pinocchio::JointModelPrismaticTpl<double, 0, 1>, pinocchio::JointModelPrismaticTpl<double, 0, 2>, pinocchio::JointModelPrismaticUnalignedTpl<double, 0>, pinocchio::JointModelTranslationTpl<double, 0>, pinocchio::JointModelRevoluteUnboundedTpl<double, 0, 0>, pinocchio::JointModelRevoluteUnboundedTpl<double, 0, 1>, pinocchio::JointModelRevoluteUnboundedTpl<double, 0, 2>, pinocchio::JointModelRevoluteUnboundedUnalignedTpl<double, 0>, boost::recursive_wrapper<pinocchio::JointModelCompositeTpl<double, 0, pinocchio::JointCollectionDefaultTpl> >, boost::detail::variant::void_, boost::detail::variant::void_, boost::detail::variant::void_, boost::detail::variant::void_, boost::detail::variant::void_, boost::detail::variant::void_, boost::detail::variant::void_, boost::detail::variant::void_, boost::detail::variant::void_> roottype, bool verbose)
    __init__(_object*, pinocchio::ModelTpl<double, 0, pinocchio::JointCollectionDefaultTpl> Pinocchio Model, bool verbose)
    __init__(_object*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > filename, std::vector<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, std::allocator<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > > > package_dir, bool verbose)

I identified the problem as being a new wrapping from pinocchio of the JointModelVariant.
I will try to propose a PR asap.

Add position bounds on the ODRI quadruped

Hi,
I would like to add position bounds to the knees of the quadruped to prevent the legs to turn around themselves.
I would like to know where the position bounds are taken into account in tsid ?
I have tried to modify a copy of the robot.model.lowerPositionLimits and the robot.model.upperPositionLimits and then set it as new model when using tsid but the new boundaries were not taken into account.
I have also thought of adding a new task using TaskJointBounds but we can not set Position bounds with this task (only velocity or acceleration bounds).
If you have an answer or some leads I could look into, that would be amazing.
Thanks for your advices.

Problem with constructor delegration for Contact6D on macOS.

Compiling current master (813bea98aab69b0) on macOS is broken. This seems to the stricter error / spec handling of clang over gcc. The error is:

o CMakeFiles/tsid.dir/solvers/solver-HQP-factory.cpp.o -c /Users/jviereck/dev/tools/tsid/src/solvers/solver-HQP-factory.cpp
/Users/jviereck/dev/tools/tsid/src/contacts/contact-6d.cpp:64:5: error: delegating constructors are permitted only in C++11
    Contact6d(name, robot, frameName, contactPoints, contactNormal, frictionCoefficient, minNormalForce, maxNormalForce)
    ^~~~~~~~~

When enabling C++11 in CMakeLists.txt as

set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")

things compile properly.

Force discontinuities when adding contact

Hello,
When adding a new contact, the contact forces of the other contacts computed by the InverseDynamicsFormulationAccForce solver are discontinuous. See the plot below that shows the forces along z of the 4 feet of a quadrupedal. At the beginning, only 3 feet are in contact, at t=6.10 the LF foot create contact.

contact_normal_force

As you can see, the total force is immediately (in one iteration) distributed between the 4 contacts, which create discontinuities.

Is there any way in the current implementation to have a 'smooth' change of the force distribution after adding a new contact or do I have to compute a force reference myself and send it with contact.setForceReference() ?

Python invdyn.getContactForces assumes 12dim contact

When calling the invdyn.checkContact(contact.name, sol) and invdyn.getContact(contact.name, sol) for a ContactPoint, there is an assertion error at

#4  0x00007fffc8496682 in tsid::InverseDynamicsFormulationAccForce::getContactForces (this=0x1bd8980, 
    name="BL_contact", sol=..., f=...)
    at /home/jviereck/dev/tools/tsid/src/formulations/inverse-dynamics-formulation-acc-force.cpp:468
468	      assert(f.size()==k);
(gdb) p f.size
$1 = {Eigen::EigenBase<Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0, Eigen::InnerStride<1> > >::Index (const Eigen::EigenBase<Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0, Eigen::InnerStride<1> > > * const)} 0x7fffc8200b0a
     <Eigen::EigenBase<Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0, Eigen::InnerStride<1> > >::size() const>
(gdb) p f.size()
$2 = 12
(gdb) p k
$3 = 3
(gdb) list
463	  for(std::vector<ContactLevel*>::iterator it=m_contacts.begin(); it!=m_contacts.end(); it++)
464	  {
465	    if((*it)->contact.name()==name)
466	    {
467	      const int k = (*it)->contact.n_force();
468	      assert(f.size()==k);
469	      f = m_f.segment((*it)->index, k);
470	      return true;
471	    }
472	  }

That is as the python wrapper calls the getContactForces method with a 12 dimensional force vector, though a ContactPoint has only 3 dimensional force vector. See 1.

@andreadelprete, so you have a good idea how to solve this? One way would be to add a way from python / C++ to query the dimension of the contact. Once the dimensionality is obtained, call the getContactForce with the right sized vector.

Dependency to gepetto viewer corba.

Would it be nice to have a dependency to the gepetto viewer, such that we can make sure that the appropriate package has been installed. If this is not relevant here we could do another meta package.
Best,
Olivier.

[task-se3-equality] Jdot_qdot term

Hi @andreadelprete ,

I want to implement a Cartesian constrain inside TSID, to be able later to perform a constraint on the convex hull (a cartesian constraint on CoM).

I have taken a look at the Cartesian task: task-se3-equality
And regarding the current implementation, I got a question concerning how the matrix A and vector b are computed.

    m_constraint.matrix().row(idx) = m_J.row(i);
    m_constraint.vector().row(idx) = (m_a_des - m_drift.toVector()).row(i);

Why are you not computing the term Jdot_qdot concerning the acceleration? I guess I missed something.

Cleaning of code

Before going further with the implementation of Python bindings, I will do a major clean of the code.

Mainly, I will:

  • remove useless inclusion
  • make input arguments generic when necessary
  • add Eigen define inside the CMake file
  • make unit tests independent from HRP-2. They will just depend on the ROMEO model
  • add travis support

I will add some other items progressively.

Cannot find files to run exercises

Hi there!

I'm trying to run exercises and looks like some data files are missing/invalid.

First, this is my problem with UR5 file. Even though file is there and looks reasonable, it does not work.

Shot1

Second, this is my problem with Romeo file.

Shot2

Any help will be appreciated.

Thanks,
Misha.

TSID python bindings compilation error

Hi,

I'm trying to build from source and without building python bindings everything is fine. When I try to build with python bindings I get an error. I am on Ubuntu 18.04.

/usr/include/boost/python/object/py_function.hpp:36:15: required from here
/usr/include/boost/variant/detail/make_variant_list.hpp:40:46: error: wrong number of template arguments (21, should be at least 0)
40 | typedef typename mpl::list< T... >::type type;
| ^~~~
In file included from /usr/include/boost/mpl/aux_/include_preprocessed.hpp:37,
from /usr/include/boost/mpl/list.hpp:46,
from /usr/include/boost/math/policies/policy.hpp:9,
from /usr/include/boost/math/special_functions/math_fwd.hpp:29,
from /usr/include/boost/math/special_functions/sign.hpp:17,
from /usr/include/boost/lexical_cast/detail/inf_nan.hpp:34,
from /usr/include/boost/lexical_cast/detail/converter_lexical_streams.hpp:63,
from /usr/include/boost/lexical_cast/detail/converter_lexical.hpp:54,
from /usr/include/boost/lexical_cast/try_lexical_convert.hpp:42,
from /usr/include/boost/lexical_cast.hpp:32,
from /usr/include/boost/python/operators.hpp:19,
from /usr/include/boost/python.hpp:49,
from /home/dan/Dev/tsid/build-RELEASE/include/tsid/bindings/python/contacts/contact-6d.hpp:21,
from /home/dan/Dev/tsid/bindings/python/contacts/contact-6d.cpp:18:
/usr/include/boost/mpl/aux
/preprocessed/gcc/list.hpp:22:8: note: provided for ‘template<class T0, class T1, class T2, class T3, class T4, class T5, class T6, class T7, class T8, class T9, class T10, class T11, class T12, class T13, class T14, class T15, class T16, class T17, class T18, class T19> struct boost::mpl::list’
22 | struct list;
| ^~~~
In file included from /usr/include/boost/variant.hpp:17,
from /usr/local/include/pinocchio/multibody/joint/joint-collection.hpp:11,
from /usr/local/include/pinocchio/multibody/joint/joint-generic.hpp:8,
from /usr/local/include/pinocchio/multibody/model.hpp:17,
from /home/dan/Dev/tsid/include/tsid/tasks/task-se3-equality.hpp:25,
from /home/dan/Dev/tsid/include/tsid/contacts/contact-6d.hpp:23,
from /home/dan/Dev/tsid/build-RELEASE/include/tsid/bindings/python/contacts/contact-6d.hpp:26,
from /home/dan/Dev/tsid/bindings/python/contacts/contact-6d.cpp:18:
/usr/include/boost/variant/variant.hpp: In instantiation of ‘typename Visitor::result_type boost::variant<T0, TN>::internal_apply_visitor(Visitor&) [with Visitor = boost::detail::variant::destroyer; T0
= pinocchio::JointDataRevoluteTpl<double, 0, 0>; TN = {pinocchio::JointDataRevoluteTpl<double, 0, 1>, pinocchio::JointDataRevoluteTpl<double, 0, 2>, pinocchio::JointDataMimic<pinocchio::JointDataRevoluteTpl<double, 0, 0> >, pinocchio::JointDataMimic<pinocchio::JointDataRevoluteTpl<double, 0, 1> >, pinocchio::JointDataMimic<pinocchio::JointDataRevoluteTpl<double, 0, 2> >, pinocchio::JointDataFreeFlyerTpl<double, 0>, pinocchio::JointDataPlanarTpl<double, 0>, pinocchio::JointDataRevoluteUnalignedTpl<double, 0>, pinocchio::JointDataSphericalTpl<double, 0>, pinocchio::JointDataSphericalZYXTpl<double, 0>, pinocchio::JointDataPrismaticTpl<double, 0, 0>, pinocchio::JointDataPrismaticTpl<double, 0, 1>, pinocchio::JointDataPrismaticTpl<double, 0, 2>, pinocchio::JointDataPrismaticUnalignedTpl<double, 0>, pinocchio::JointDataTranslationTpl<double, 0>, pinocchio::JointDataRevoluteUnboundedTpl<double, 0, 0>, pinocchio::JointDataRevoluteUnboundedTpl<double, 0, 1>, pinocchio::JointDataRevoluteUnboundedTpl<double, 0, 2>, pinocchio::JointDataRevoluteUnboundedUnalignedTpl<double, 0>, boost::recursive_wrapper<pinocchio::JointDataCompositeTpl<double, 0, pinocchio::JointCollectionDefaultTpl> >}; typename Visitor::result_type = void]’:
/usr/include/boost/variant/variant.hpp:1414:9: required from ‘void boost::variant<T0, TN>::destroy_content() [with T0_ = pinocchio::JointDataRevoluteTpl<double, 0, 0>; TN = {pinocchio::JointDataRevoluteTpl<double, 0, 1>, pinocchio::JointDataRevoluteTpl<double, 0, 2>, pinocchio::JointDataMimic<pinocchio::JointDataRevoluteTpl<double, 0, 0> >, pinocchio::JointDataMimic<pinocchio::JointDataRevoluteTpl<double, 0, 1> >, pinocchio::JointDataMimic<pinocchio::JointDataRevoluteTpl<double, 0, 2> >, pinocchio::JointDataFreeFlyerTpl<double, 0>, pinocchio::JointDataPlanarTpl<double, 0>, pinocchio::JointDataRevoluteUnalignedTpl<double, 0>, pinocchio::JointDataSphericalTpl<double, 0>, pinocchio::JointDataSphericalZYXTpl<double, 0>, pinocchio::JointDataPrismaticTpl<double, 0, 0>, pinocchio::JointDataPrismaticTpl<double, 0, 1>, pinocchio::JointDataPrismaticTpl<double, 0, 2>, pinocchio::JointDataPrismaticUnalignedTpl<double, 0>, pinocchio::JointDataTranslationTpl<double, 0>, pinocchio::JointDataRevoluteUnboundedTpl<double, 0, 0>, pinocchio::JointDataRevoluteUnboundedTpl<double, 0, 1>, pinocchio::JointDataRevoluteUnboundedTpl<double, 0, 2>, pinocchio::JointDataRevoluteUnboundedUnalignedTpl<double, 0>, boost::recursive_wrapper<pinocchio::JointDataCompositeTpl<double, 0, pinocchio::JointCollectionDefaultTpl> >}]’
/usr/include/boost/variant/variant.hpp:1421:9: required from ‘boost::variant<T0, TN>::~variant() [with T0_ = pinocchio::JointDataRevoluteTpl<double, 0, 0>; TN = {pinocchio::JointDataRevoluteTpl<double, 0, 1>, pinocchio::JointDataRevoluteTpl<double, 0, 2>, pinocchio::JointDataMimic<pinocchio::JointDataRevoluteTpl<double, 0, 0> >, pinocchio::JointDataMimic<pinocchio::JointDataRevoluteTpl<double, 0, 1> >, pinocchio::JointDataMimic<pinocchio::JointDataRevoluteTpl<double, 0, 2> >, pinocchio::JointDataFreeFlyerTpl<double, 0>, pinocchio::JointDataPlanarTpl<double, 0>, pinocchio::JointDataRevoluteUnalignedTpl<double, 0>, pinocchio::JointDataSphericalTpl<double, 0>, pinocchio::JointDataSphericalZYXTpl<double, 0>, pinocchio::JointDataPrismaticTpl<double, 0, 0>, pinocchio::JointDataPrismaticTpl<double, 0, 1>, pinocchio::JointDataPrismaticTpl<double, 0, 2>, pinocchio::JointDataPrismaticUnalignedTpl<double, 0>, pinocchio::JointDataTranslationTpl<double, 0>, pinocchio::JointDataRevoluteUnboundedTpl<double, 0, 0>, pinocchio::JointDataRevoluteUnboundedTpl<double, 0, 1>, pinocchio::JointDataRevoluteUnboundedTpl<double, 0, 2>, pinocchio::JointDataRevoluteUnboundedUnalignedTpl<double, 0>, boost::recursive_wrapper<pinocchio::JointDataCompositeTpl<double, 0, pinocchio::JointCollectionDefaultTpl> >}]’
/usr/local/include/pinocchio/multibody/joint/joint-generic.hpp:68:10: required from ‘void __gnu_cxx::new_allocator<_Tp>::destroy(_Up*) [with _Up = pinocchio::JointDataTpl; _Tp = pinocchio::JointDataTpl]’
/usr/include/c++/9/bits/alloc_traits.h:260:4: required from ‘static decltype (__a.destroy(__p)) std::allocator_traits<_Alloc>::_S_destroy(_Alloc2&, _Tp*, int) [with _Alloc2 = Eigen::aligned_allocator<pinocchio::JointDataTpl >; _Tp = pinocchio::JointDataTpl; _Alloc = Eigen::aligned_allocator<pinocchio::JointDataTpl >; decltype (__a.destroy(__p)) = void]’
/usr/include/c++/9/bits/alloc_traits.h:364:14: required from ‘static void std::allocator_traits<_Alloc>::destroy(_Alloc&, _Tp*) [with Tp = pinocchio::JointDataTpl; Alloc = Eigen::aligned_allocator<pinocchio::JointDataTpl >]’
/usr/include/c++/9/bits/stl_construct.h:198:19: [ skipping 3 instantiation contexts, use -ftemplate-backtrace-limit=0 to disable ]
/usr/include/boost/python/detail/destroy.hpp:52:15: required from ‘void boost::python::detail::destroy_referent_impl(void*, T& ()()) [with T = const pinocchio::DataTpl]’
/usr/include/boost/python/detail/destroy.hpp:58:26: required from ‘void boost::python::detail::destroy_referent(void
, T ()()) [with T = const pinocchio::DataTpl&]’
/usr/include/boost/python/converter/rvalue_from_python_data.hpp:135:51: required from ‘boost::python::converter::rvalue_from_python_data::~rvalue_from_python_data() [with T = const pinocchio::DataTpl&]’
/usr/include/boost/python/converter/arg_from_python.hpp:106:8: required from ‘PyObject
boost::python::detail::caller_arity<5>::impl<F, Policies, Sig>::operator()(PyObject*, PyObject*) [with F = tsid::math::ConstraintInequality ()(tsid::contacts::Contact6d&, double, const Eigen::Matrix<double, -1, 1>&, const Eigen::Matrix<double, -1, 1>&, const pinocchio::DataTpl&); Policies = boost::python::default_call_policies; Sig = boost::mpl::vector6<tsid::math::ConstraintInequality, tsid::contacts::Contact6d&, double, const Eigen::Matrix<double, -1, 1>&, const Eigen::Matrix<double, -1, 1>&, const pinocchio::DataTpl&>; PyObject = _object]’
/usr/include/boost/python/object/py_function.hpp:38:33: required from ‘PyObject
boost::python::objects::caller_py_function_impl::operator()(PyObject*, PyObject*) [with Caller = boost::python::detail::caller<tsid::math::ConstraintInequality (*)(tsid::contacts::Contact6d&, double, const Eigen::Matrix<double, -1, 1>&, const Eigen::Matrix<double, -1, 1>&, const pinocchio::DataTpl&), boost::python::default_call_policies, boost::mpl::vector6<tsid::math::ConstraintInequality, tsid::contacts::Contact6d&, double, const Eigen::Matrix<double, -1, 1>&, const Eigen::Matrix<double, -1, 1>&, const pinocchio::DataTpl&> >; PyObject = object]’
/usr/include/boost/python/object/py_function.hpp:36:15: required from here
/usr/include/boost/variant/variant.hpp:2407:41: error: using invalid field ‘boost::variant<T0, TN>::storage

2407 | which
, which(), visitor, storage
.address()
| ^~~~~~~~
/usr/include/boost/variant/variant.hpp:2408:13: error: return-statement with a value, in function returning ‘boost::static_visitor<>::result_type’ {aka ‘void’} [-fpermissive]
2408 | );
| ^
bindings/python/CMakeFiles/tsid_pywrap.dir/build.make:137: recipe for target 'bindings/python/CMakeFiles/tsid_pywrap.dir/contacts/contact-6d.cpp.o' failed
make[2]: *** [bindings/python/CMakeFiles/tsid_pywrap.dir/contacts/contact-6d.cpp.o] Error 1
make[2]: Leaving directory '/home/dan/Dev/tsid/_build-RELEASE'
CMakeFiles/Makefile2:546: recipe for target 'bindings/python/CMakeFiles/tsid_pywrap.dir/all' failed
make[1]: *** [bindings/python/CMakeFiles/tsid_pywrap.dir/all] Error 2
make[1]: Leaving directory '/home/dan/Dev/tsid/_build-RELEASE'
Makefile:143: recipe for target 'all' failed
make: *** [all] Error 2

I think it might be to do with boost - when I try to install tsid using

sudo apt-get install robotpkg-tsid

I get the following error

Reading package lists... Done
Building dependency tree
Reading state information... Done
Some packages could not be installed. This may mean that you have
requested an impossible situation or if you are using the unstable
distribution that some required packages have not yet been created
or been moved out of Incoming.
The following information may help to resolve the situation:
The following packages have unmet dependencies.
robotpkg-tsid : Depends: robotpkg-pinocchio (= 1.2.4r2) but it is not going to be installed or
robotpkg-pinocchio (= 1.2.6) but it is not going to be installed or
robotpkg-pinocchio (= 1.2.5r1) but it is not going to be installed or
robotpkg-pinocchio (= 1.2.4r3) but it is not going to be installed or
robotpkg-pinocchio (= 1.2.6r1) but it is not going to be installed
Depends: libboost-test1.58-dev (>= 1.34.1) but it is not installable
Depends: libboost-test1.58.0 (>= 1.34.1) but it is not installable
E: Unable to correct problems, you have held broken packages.

I have seen a similar issue on pinocchio github. stack-of-tasks/pinocchio#837

Any help would be appreciated.

Thanks!

error from demo_romeo.py

Hi,
I am trying to use TSID for generating whole body quadruped motion.
After installing the TSID, I run the demo_romeo.py.

There was a error message which can see in below.
image

It seems that the version of pinocchio is not updated, so I change "getNeutralConfiguration" to "neutral" function.
After that, there was also another error message.
image

Could you tell me how to fix it?

demo_romeo does not run with latest pinocchio, gepetto-gui, gepetto-viewer-corba

Likely due to a change in the Pinocchio API?

$ ipython demo/demo_romeo.py
####################################################################################################
################################# Test Task Space Inverse Dynamics #################################
#################################################################################################### 

---------------------------------------------------------------------------
AttributeError                            Traceback (most recent call last)
/home/wxm/dev/pinocchio_ws/tsid/demo/demo_romeo.py in <module>()
     52 
     53 # for gepetto viewer .. but Fix me!!
---> 54 robot_display = se3.RobotWrapper(urdf, [path, ], se3.JointModelFreeFlyer())
     55 
     56 l = commands.getstatusoutput("ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l")

/home/wxm/.local/lib/python2.7/site-packages/pinocchio/robot_wrapper.pyc in __init__(self, model, collision_model, visual_model, verbose)
     50 
     51         self.model = model
---> 52         self.data = self.model.createData()
     53 
     54         self.collision_model = collision_model

AttributeError: 'str' object has no attribute 'createData'

compiling problem

Problem Description
My OS is Ubuntu18.04.
First, I installed PInocchio successfully following the instructions on this website https://stack-of-tasks.github.io/pinocchio/download.html :

  1. Add robotpkg apt repository
  2. Install Pinocchio
    sudo apt install robotpkg-py27-pinocchio
  3. Configure environment variables(add the following to the file ~/.bashrc and source it)
    export PATH=/opt/openrobots/bin:$PATH
    export PKG_CONFIG_PATH=/opt/openrobots/lib/pkgconfig:$PKG_CONFIG_PATH
    export LD_LIBRARY_PATH=/opt/openrobots/lib:$LD_LIBRARY_PATH
    export PYTHONPATH=/opt/openrobots/lib/python2.7/site-packages:$PYTHONPATH
    Then, I started installing tsid following the instructions on this website and failed when executing cmake:
    Screenshot from 2019-10-12 14-31-03
    I am really confused.

Test inconsistent

Exercises instructions

A few glitches after the class on TSID:

  • line
    sudo apt-get install robotpkg-omniorbpy=3.1r3</code></pre>
    is not needed. robotpkg-py27-...-...-corba only depends on omniORB from the official repositories.
  • for some obscure reasons, virtualenv removes /usr/lib/python2.7/dist-packages from PYTHONPATH. You may want to add a warning in the instructions.

BSD License

Dear all,
We will soon switch to BSD License v2.0 to ease our collaborations.
Let me know if there is a problem with this.
Cheers,
Olivier.

support for 3D contacts models?

To handle quadruped robots such as HyQ in tsid, we had to modify the urdf files of the robot by adding virtual joints that allow to represent the 3D contacts of the robot as a 6D ones.

(urdf here: https://github.com/humanoid-path-planner/hpp-rbprm-robot-data/blame/master/data/hyq_description/urdf/hyq_contact6D.urdf)

While this might be useful to further constrain inclination of the leg when the robot is in contact,
this can be problematic in the general case.

Do you think we should extend tsid to handle 3D contacts or not ?

Python binding of RobotWrapper for devel branch

Dear all,

I am working on the devel branch to get the recent commits related to Python 3 compatibility. I ran into an issue with Python binding for tsid.RobotWrapper. This issue has already been raised in #50 and corrected by the PR #51 but only for the master branch so you will likely get this error when testing the scripts on the devel branch.

A quick solution for that if you are on devel is git cherry-pick 761194b. It is just to warn you if you have this issue in the future.

Best,

[Cmake] catkin_package required for installation

Dear all,

I ran into an issue trying to install TSID. It is asking for catkin-pkg but this package is not in the dependencies of the main page.

It seems there is some discussion going on about catkin preventing packaging in #48 involving the following lines in CMakeList.txt.

# Fail-safe support for catkin-ized pinocchio:
#  - If catkin-based pinocchio is installed it runs the CFG_EXTRAS to set up the Pinocchio preprocessor directives
#  - If it isn't, nothing happens and the subsequent pkg-config check takes care of everything.
find_package(catkin QUIET COMPONENTS pinocchio)

Looks like it is not supposed to block me if I do not have catkin_pkg.

Here is the output of my terminal:

cmake .. -DCMAKE_BUILD_TYPE=RELEASE -DCMAKE_INSTALL_PREFIX=/local/users/paleziart -DPYTHON_EXECUTABLE=$(which python3.5) -DPYTHON_STANDARD_LAYOUT=ON
-- The C compiler identification is GNU 5.4.0
-- The CXX compiler identification is GNU 5.4.0
-- Check for working C compiler: /usr/bin/cc
-- Check for working C compiler: /usr/bin/cc -- works
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Detecting C compile features
-- Detecting C compile features - done
-- Check for working CXX compiler: /usr/bin/c++
-- Check for working CXX compiler: /usr/bin/c++ -- works
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Found PkgConfig: /usr/bin/pkg-config (found version "0.29.1") 
-- Performing Test R-pedantic
-- Performing Test R-pedantic - Success
-- Performing Test R-Wno-long-long
-- Performing Test R-Wno-long-long - Success
-- Performing Test R-Wall
-- Performing Test R-Wall - Success
-- Performing Test R-Wextra
-- Performing Test R-Wextra - Success
-- Performing Test R-Wcast-align
-- Performing Test R-Wcast-align - Success
-- Performing Test R-Wcast-qual
-- Performing Test R-Wcast-qual - Success
-- Performing Test R-Wformat
-- Performing Test R-Wformat - Success
-- Performing Test R-Wwrite-strings
-- Performing Test R-Wwrite-strings - Success
-- Performing Test R-Wconversion
-- Performing Test R-Wconversion - Success
-- Found Doxygen: /usr/bin/doxygen (found version "1.8.11") 
-- Option EIGEN_RUNTIME_NO_MALLOC on.
-- eigen3 >= 3.2.0 is required.
-- Checking for module 'eigen3 >= 3.2.0'
--   Found eigen3 , version 3.2.92
-- Pkg-config module eigen3 v3.2.92 has been detected with success.
-- Using CATKIN_DEVEL_PREFIX: /local/users/paleziart/tsid/_build-RELEASE/devel
-- Using CMAKE_PREFIX_PATH: /opt/ros/kinetic
-- This workspace overlays: /opt/ros/kinetic
-- Found PythonInterp: /usr/bin/python3.5 (found suitable version "3.5.2", minimum required is "2") 
-- Using PYTHON_EXECUTABLE: /usr/bin/python3.5
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /local/users/paleziart/tsid/_build-RELEASE/test_results
-- Found gtest sources under '/usr/src/gmock': gtests will be built
-- Found gmock sources under '/usr/src/gmock': gmock will be built
-- Found PythonInterp: /usr/bin/python3.5 (found version "3.5.2") 
-- Using Python nosetests: /usr/bin/nosetests
ImportError: "from catkin_pkg.package import parse_package" failed: No module named 'catkin_pkg'
Make sure that you have installed "catkin_pkg", it is up to date and on the PYTHONPATH.
CMake Error at /opt/ros/kinetic/share/catkin/cmake/safe_execute_process.cmake:11 (message):
  execute_process(/usr/bin/python3.5
  "/opt/ros/kinetic/share/catkin/cmake/parse_package_xml.py"
  "/opt/ros/kinetic/share/catkin/cmake/../package.xml"
  "/local/users/paleziart/tsid/_build-RELEASE/catkin/catkin_generated/version/package.cmake")
  returned error code 1
Call Stack (most recent call first):
  /opt/ros/kinetic/share/catkin/cmake/catkin_package_xml.cmake:74 (safe_execute_process)
  /opt/ros/kinetic/share/catkin/cmake/all.cmake:168 (_catkin_package_xml)
  /opt/ros/kinetic/share/catkin/cmake/catkinConfig.cmake:20 (include)
  CMakeLists.txt:80 (find_package)

-- Configuring incomplete, errors occurred!
See also "/local/users/paleziart/tsid/_build-RELEASE/CMakeFiles/CMakeOutput.log".
See also "/local/users/paleziart/tsid/_build-RELEASE/CMakeFiles/CMakeError.log".

MemoryError using Python bindings

Hi,
I installed tsid and its python bindings successfully. But when I try to run the test script 'ipython script/test_formulation.py'. The python gives me the error 'MemoryError'.
image
The same happens when I ran another test script:
image

I checked my memory and it has plenty. Also, I checked the version of Python, it is 64 bit. So I cannot figure out why...

BTW, when I want to switch to C++, I find very few examples and almost no tutorial, so I think python is the main language of the library, but any examples for C++?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.