stack-of-tasks / pinocchio

A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
http://stack-of-tasks.github.io/pinocchio/
BSD 2-Clause "Simplified" License
1.78k stars 375 forks source link

Compute gravity with c++ api wrong #1514

Closed YaoweiFan closed 3 years ago

YaoweiFan commented 3 years ago

I use python api to compute the gravity and the result is [-0.11936972 0.98543975 0. 0.9855705 0.03554471 -0.05846138]. That's what I expected.

q = np.asarray([0, 0, 0, 1.57, 0, 0])
v = pinocchio.utils.zero(model.nv)
a = pinocchio.utils.zero(model.nv)
gravity = pinocchio.rnea(model,data,q,v,a)

I use c++ api to compute the gravity of the same model, but the result is [0 0 0 0 0 0].

const std::string urdf_filename = "six_arm_hand/urdf/six_arm_hand_no_palm.urdf";
pinocchio::urdf::buildModel(urdf_filename, model);
pinocchio::Data data(model);
Eigen::VectorXd q = pinocchio::neutral(model);
Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv);
Eigen::VectorXd a = Eigen::VectorXd::Zero(model.nv);
q << 0, 0, 0, 1.57, 0, 0;
gravity = pinocchio::rnea(model, data, q, v, a);

What's wrong in my c++ code? Could you give me some hints?

jcarpent commented 3 years ago

Could you share with us your model?

proyan commented 3 years ago

What is the full python code (including where you load the robot)?

proyan commented 3 years ago

Also, if it is possible, provide us a copy of your model. Also, run

pinocchio.computeGeneralizedGravity(model, data, q)

and compare the output with the c++ and python versions

YaoweiFan commented 3 years ago

This is my full python code:

import sys
from os.path import dirname, join, abspath
import pinocchio
import numpy as np

model_dir = dirname(dirname(abspath(__file__)))
urdf_file_path = join(model_dir, '../six_arm_hand/urdf/six_arm_hand_no_palm.urdf')
model = pinocchio.buildModelFromUrdf(urdf_file_path)
data = model.createData()
v = pinocchio.utils.zero(model.nv)
a = pinocchio.utils.zero(model.nv)

if __name__ == '__main__':
    q = np.asarray([0, 0, 0, 1.57, 0, 0])
    gravity = pinocchio.rnea(model,data,q,v,a)
    print gravity

This is my model:

<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com) 
     Commit Version: 1.5.1-0-g916b5db  Build Version: 1.5.7152.31018
     For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
  name="six_arm_hand">
  <link
    name="base_link">
    <inertial>
      <origin
        xyz="6.3562527179902E-05 -0.00590971793251037 0.843647614040915"
        rpy="0 0 0" />
      <mass
        value="10.6875075459949" />
      <inertia
        ixx="0.369166290134353"
        ixy="-1.09800431762322E-08"
        ixz="-2.65717180673806E-05"
        iyy="0.366929421492863"
        iyz="-4.40923295784043E-11"
        izz="0.0155303148832649" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/base_link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/base_link.STL" />
      </geometry>
    </collision>
  </link>

  <link name="link_f"/>

  <joint name="fixed_link_f_joint" type="fixed">
    <parent link="world"/>
    <child link="link_f"/>
    <origin
      xyz="0 -0.237 1.18"
      rpy="0 0 0" />
  </joint>

  <link name="world"/>
  <joint name="fixed_base_joint" type="fixed">
    <parent link="world"/>
    <child link="base_link"/>
  </joint>
  <link
    name="shoulderPitch_Link">
    <inertial>
      <origin
        xyz="0.00564619322967518 -0.0388011617673537 2.59837315486067E-06"
        rpy="0 0 0" />
      <mass
        value="0.46726632049004" />
      <inertia
        ixx="0.000399813771841688"
        ixy="3.18591804143914E-05"
        ixz="-5.46038795579012E-10"
        iyy="0.00028754222084699"
        iyz="1.36442767870995E-06"
        izz="0.000254117183590909" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/shoulderPitch_Link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/shoulderPitch_Link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="shoulderPitch"
    type="revolute">
    <origin
      xyz="8.8679E-05 -0.185 1.18"
      rpy="0 0 0" />
    <parent
      link="base_link" />
    <child
      link="shoulderPitch_Link" />
    <axis
      xyz="0 1 0" />
    <limit
      lower="-3.55"
      upper="0.4"
      effort="1"
      velocity="0.5" />
  </joint>
  <link
    name="shoulderRoll_Link">
    <inertial>
      <origin
        xyz="-0.0199126166365459 2.89601151149954E-05 -0.0740087713535413"
        rpy="0 0 0" />
      <mass
        value="0.419772107473911" />
      <inertia
        ixx="0.000433353050610292"
        ixy="-2.69038724505281E-07"
        ixz="-6.24263594181734E-05"
        iyy="0.000408481342435734"
        iyz="-1.66550940469567E-08"
        izz="0.000192251180848283" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/shoulderRoll_Link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/shoulderRoll_Link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="shoulderRoll"
    type="revolute">
    <origin
      xyz="0.035 -0.052 0"
      rpy="0 0 0" />
    <parent
      link="shoulderPitch_Link" />
    <child
      link="shoulderRoll_Link" />
    <axis
      xyz="-1 0 0" />
    <limit
      lower="0"
      upper="3.14"
      effort="1"
      velocity="0.5" />
  </joint>
  <link
    name="shoulderYaw_Link">
    <inertial>
      <origin
        xyz="0.00656055179830629 2.90440103517531E-06 -0.10861093303565"
        rpy="0 0 0" />
      <mass
        value="0.403452087830578" />
      <inertia
        ixx="0.000244599346494787"
        ixy="1.67313795390288E-08"
        ixz="8.78933058031097E-06"
        iyy="0.000203262269064636"
        iyz="-7.30893918984527E-07"
        izz="0.000136352484194931" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/shoulderYaw_Link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/shoulderYaw_Link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="shoulderYaw"
    type="revolute">
    <origin
      xyz="-0.035009 0 -0.116"
      rpy="0 0 0" />
    <parent
      link="shoulderRoll_Link" />
    <child
      link="shoulderYaw_Link" />
    <axis
      xyz="0 0 1" />
    <limit
      lower="-3.14"
      upper="3.14"
      effort="1"
      velocity="0.5" />
  </joint>
  <link
    name="elbowRoll_Link">
    <inertial>
      <origin
        xyz="-0.00738820409777829 -1.00321901477796E-06 -0.0593095691808454"
        rpy="0 0 0" />
      <mass
        value="0.151796397464374" />
      <inertia
        ixx="0.000189801415883418"
        ixy="-3.17669130469068E-10"
        ixz="-3.78850276737954E-05"
        iyy="0.000182437215525365"
        iyz="-1.37670316430067E-09"
        izz="8.44118119449699E-05" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/elbowRoll_Link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/elbowRoll_Link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="elbowRoll"
    type="revolute">
    <origin
      xyz="0.034989 0 -0.144"
      rpy="0 0 0" />
    <parent
      link="shoulderYaw_Link" />
    <child
      link="elbowRoll_Link" />
    <axis
      xyz="-1 0 0" />
    <limit
      lower="-1.57"
      upper="0.0"
      effort="1"
      velocity="0.5" />
  </joint>
  <link
    name="wristYaw_Link">
    <inertial>
      <origin
        xyz="-0.0110072042858961 9.00744748022486E-06 -0.0919568730668572"
        rpy="0 0 0" />
      <mass
        value="0.335351440910377" />
      <inertia
        ixx="0.000196408493546082"
        ixy="6.85439502098526E-08"
        ixz="-6.68611866426507E-07"
        iyy="0.000192751420074017"
        iyz="4.5521068979922E-08"
        izz="0.000114531535457464" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/wristYaw_Link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/wristYaw_Link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="wristYaw"
    type="revolute">
    <origin
      xyz="-0.035008 0 -0.101"
      rpy="0 0 0" />
    <parent
      link="elbowRoll_Link" />
    <child
      link="wristYaw_Link" />
    <axis
      xyz="0 0 1" />
    <limit
      lower="-3.14"
      upper="3.14"
      effort="1"
      velocity="0.5" />
  </joint>
  <link
    name="wristPitch_Link">
    <inertial>
      <origin
        xyz="0.000861733289080682 0.0016812764550127 -0.0745105520843234"
        rpy="0 0 0" />
      <mass
        value="0.0799816292892163" />
      <inertia
        ixx="2.50894522854529E-05"
        ixy="-1.27452216950587E-07"
        ixz="1.3290884331058E-06"
        iyy="3.68917834676378E-05"
        iyz="-3.66388617266229E-09"
        izz="1.4492968393251E-05" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/wristPitch_Link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://six_arm_hand/meshes/wristPitch_Link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="wristPitch"
    type="revolute">
    <origin
      xyz="-1.1949E-05 0 -0.159"
      rpy="0 0 0" />
    <parent
      link="wristYaw_Link" />
    <child
      link="wristPitch_Link" />
    <axis
      xyz="1 0 0" />
    <limit
      lower="-1.3"
      upper="1.3"
      effort="1"
      velocity="0.5" />
  </joint>

</robot>
YaoweiFan commented 3 years ago

I run the c++ version and get [0 0 0 0 0 0].

pinocchio::computeGeneralizedGravity(model, data, q);

I run the python version and get [-0.11936972 0.98543975 0 0.9855705 0.03554471 -0.05846138].

pinocchio.computeGeneralizedGravity(model, data, q);

Just like rnea function.

jcarpent commented 3 years ago

Could you also share your full C++ code?

YaoweiFan commented 3 years ago

Here is my C++ code:

#include <pinocchio/fwd.hpp>
#include "pinocchio/parsers/urdf.hpp"
#include "pinocchio/algorithm/rnea.hpp"
#include "pinocchio/algorithm/frames.hpp"
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/algorithm/joint-configuration.hpp"

#include <ros/ros.h>
#include <sensor_msgs/JointState.h>

#include <string>
#include <Eigen/Dense>

pinocchio::Model model;

int main(int argc, char **argv)
{
    // Load the urdf model
    const std::string urdf_filename = "single_arm_ws/src/six_arm_hand/urdf/six_arm_hand_no_palm.urdf";
    pinocchio::urdf::buildModel(urdf_filename, model);

    pinocchio::Data data(model);

    Eigen::VectorXd q = pinocchio::neutral(model);
    Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv);
    Eigen::VectorXd a = Eigen::VectorXd::Zero(model.nv);
    q << 0, 0, 0, 1.57, 0, 0;
    std::cout << "gravity:"<< std::endl << pinocchio::rnea(model, data, q, v, a) << std::endl;

    ros::waitForShutdown();
}
jcarpent commented 3 years ago

On my side this is working perfectly:

gravity:
  -0.11937
   0.98544
         0
   0.98557
 0.0355447
-0.0584614
jcarpent commented 3 years ago

Here is the code I've been using:

#include <pinocchio/fwd.hpp>
#include "pinocchio/parsers/urdf.hpp"
#include "pinocchio/algorithm/rnea.hpp"
#include "pinocchio/algorithm/frames.hpp"
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/algorithm/joint-configuration.hpp"

#include <iostream>

pinocchio::Model model;

int main(int argc, char **argv)
{
    // Load the urdf model
    const std::string urdf_filename = "model.urdf";
    pinocchio::urdf::buildModel(urdf_filename, model);

    pinocchio::Data data(model);

    Eigen::VectorXd q = pinocchio::neutral(model);
    Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv);
    Eigen::VectorXd a = Eigen::VectorXd::Zero(model.nv);
    q << 0, 0, 0, 1.57, 0, 0;
    std::cout << "gravity:"<< std::endl << pinocchio::rnea(model, data, q, v, a) << std::endl;

}

with compilation line: g++ code.cpp -o test $(pkg-config --cflags pinocchio) $(pkg-config --libs pinocchio)

proyan commented 3 years ago

This is interesting. I can duplicate the error in c++, using both Justin's and @YaoweiFan's version.

I don't have an explanation for it, but if I remove the global variable model and move it within the main() function, I don't have this error anymore.

@YaoweiFan Could you try the following code and tell me that it works?

#include <pinocchio/fwd.hpp>
#include "pinocchio/parsers/urdf.hpp"
#include "pinocchio/algorithm/rnea.hpp"
#include "pinocchio/algorithm/frames.hpp"
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/algorithm/joint-configuration.hpp"

#include <iostream>

int main(int argc, char **argv)
{
    // Load the urdf model
  pinocchio::Model model;
  const std::string urdf_filename = "model.urdf";
  pinocchio::urdf::buildModel(urdf_filename, model);

  pinocchio::Data data(model);
  Eigen::VectorXd q = pinocchio::neutral(model);
  Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv);
  Eigen::VectorXd a = Eigen::VectorXd::Zero(model.nv);
  q << 0, 0, 0, 1.57, 0, 0;
  std::cout << "gravity:"<< std::endl << pinocchio::rnea(model, data, q, v, a).transpose() << std::endl;
  std::cout << "gravity generalized:"<< std::endl << pinocchio::computeGeneralizedGravity(model, data, q).transpose() << std::endl;

}

Also, for the sake of completeness, move

pinocchio::Model model;

to the global scope as before, and try the script again? You can use the command line instructions provided by Justin

proyan commented 3 years ago

When model is in the global scope, I get:

rbudhira@pl834-pro:/local/rbudhira$ ./test2 
gravity:
0 0 0 0 0 0
gravity generalized:
0 0 0 0 0 0

and when model is in the local scope, I get:

rbudhira@pl834-pro:/local/rbudhira$ ./test2 
gravity:
  -0.11937    0.98544          0    0.98557  0.0355447 -0.0584614
gravity generalized:
  -0.11937    0.98544          0    0.98557  0.0355447 -0.0584614
jcarpent commented 3 years ago

I think this seems related to your compiler. Which one is it @proyan @YaoweiFan?

jcarpent commented 3 years ago

The model.gravity field seems to not be correctly initialized in fact.

jcarpent commented 3 years ago

Could you check that @proyan?

YaoweiFan commented 3 years ago

I have tested what you told and the result is the same as yours. The reason why I set the model a global variable is that I want to use it in my callback function. So, how can I deal with this?

jcarpent commented 3 years ago

As a global pointer. @YaoweiFan What is your compiler?

YaoweiFan commented 3 years ago

g++ (Ubuntu 8.4.0-1ubuntu1~18.04) 8.4.0 And here is my ouput:

➜ g++ cartesian_impedence_controller_simplify.cpp -o test $(pkg-config --cflags pinocchio) $(pkg-config --libs pinocchio)

In file included from /usr/include/eigen3/unsupported/Eigen/CXX11/Tensor:105,
                 from /opt/openrobots/include/pinocchio/fwd.hpp:31,
                 from cartesian_impedence_controller_simplify.cpp:1:
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h: In instantiation of ‘struct Eigen::TensorEvaluator<const Eigen::Tensor<double, 3, 0, long int>, Eigen::DefaultDevice>’:
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h:232:8:   required from ‘struct Eigen::TensorEvaluator<const Eigen::TensorCwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, const Eigen::Tensor<double, 3, 0, long int> >, Eigen::DefaultDevice>’
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorAssign.h:96:70:   required from ‘struct Eigen::TensorEvaluator<const Eigen::TensorAssignOp<Eigen::Tensor<double, 3, 0, long int>, const Eigen::TensorCwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, const Eigen::Tensor<double, 3, 0, long int> > >, Eigen::DefaultDevice>’
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/Tensor.h:416:14:   required from ‘Eigen::Tensor<Scalar_, NumIndices_, Options_, IndexType>& Eigen::Tensor<Scalar_, NumIndices_, Options_, IndexType>::operator=(const OtherDerived&) [with OtherDerived = Eigen::TensorCwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, const Eigen::Tensor<double, 3, 0, long int> >; Scalar_ = double; int NumIndices_ = 3; int Options_ = 0; IndexType_ = long int]’
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h:845:24:   required from ‘Derived& Eigen::TensorBase<Derived, AccessLevel>::setConstant(const Scalar&) [with Derived = Eigen::Tensor<double, 3, 0, long int>; int AccessLevel = 1; Eigen::TensorBase<Derived, AccessLevel>::Scalar = double]’
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h:841:14:   required from ‘Derived& Eigen::TensorBase<Derived, AccessLevel>::setZero() [with Derived = Eigen::Tensor<double, 3, 0, long int>; int AccessLevel = 1]’
/opt/openrobots/include/pinocchio/multibody/data.hxx:131:5:   required from ‘pinocchio::DataTpl<Scalar, Options, JointCollectionTpl>::DataTpl(const Model&) [with _Scalar = double; int _Options = 0; JointCollectionTpl = pinocchio::JointCollectionDefaultTpl; pinocchio::DataTpl<Scalar, Options, JointCollectionTpl>::Model = pinocchio::ModelTpl<double>]’
cartesian_impedence_controller_simplify.cpp:18:31:   required from here
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h:162:71: warning: ignoring attributes on template argument ‘Eigen::PacketType<double, Eigen::DefaultDevice>::type’ {aka ‘__vector(2) double’} [-Wignored-attributes]
     PacketAccess = (internal::unpacket_traits<PacketReturnType>::size > 1),
                    ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^~~~
In file included from /usr/include/eigen3/unsupported/Eigen/CXX11/Tensor:105,
                 from /opt/openrobots/include/pinocchio/fwd.hpp:31,
                 from cartesian_impedence_controller_simplify.cpp:1:
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h: In instantiation of ‘struct Eigen::TensorEvaluator<Eigen::Tensor<double, 3, 0, long int>, Eigen::DefaultDevice>’:
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorAssign.h:100:65:   required from ‘struct Eigen::TensorEvaluator<const Eigen::TensorAssignOp<Eigen::Tensor<double, 3, 0, long int>, const Eigen::TensorCwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, const Eigen::Tensor<double, 3, 0, long int> > >, Eigen::DefaultDevice>’
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/Tensor.h:416:14:   required from ‘Eigen::Tensor<Scalar_, NumIndices_, Options_, IndexType>& Eigen::Tensor<Scalar_, NumIndices_, Options_, IndexType>::operator=(const OtherDerived&) [with OtherDerived = Eigen::TensorCwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, const Eigen::Tensor<double, 3, 0, long int> >; Scalar_ = double; int NumIndices_ = 3; int Options_ = 0; IndexType_ = long int]’
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h:845:24:   required from ‘Derived& Eigen::TensorBase<Derived, AccessLevel>::setConstant(const Scalar&) [with Derived = Eigen::Tensor<double, 3, 0, long int>; int AccessLevel = 1; Eigen::TensorBase<Derived, AccessLevel>::Scalar = double]’
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h:841:14:   required from ‘Derived& Eigen::TensorBase<Derived, AccessLevel>::setZero() [with Derived = Eigen::Tensor<double, 3, 0, long int>; int AccessLevel = 1]’
/opt/openrobots/include/pinocchio/multibody/data.hxx:131:5:   required from ‘pinocchio::DataTpl<Scalar, Options, JointCollectionTpl>::DataTpl(const Model&) [with _Scalar = double; int _Options = 0; JointCollectionTpl = pinocchio::JointCollectionDefaultTpl; pinocchio::DataTpl<Scalar, Options, JointCollectionTpl>::Model = pinocchio::ModelTpl<double>]’
cartesian_impedence_controller_simplify.cpp:18:31:   required from here
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h:42:71: warning: ignoring attributes on template argument ‘Eigen::PacketType<double, Eigen::DefaultDevice>::type’ {aka ‘__vector(2) double’} [-Wignored-attributes]
     PacketAccess = (internal::unpacket_traits<PacketReturnType>::size > 1),
                    ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^~~~
In file included from /usr/include/eigen3/unsupported/Eigen/CXX11/Tensor:139,
                 from /opt/openrobots/include/pinocchio/fwd.hpp:31,
                 from cartesian_impedence_controller_simplify.cpp:1:
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorExecutor.h: In instantiation of ‘static void Eigen::internal::TensorExecutor<Expression, Eigen::DefaultDevice, true>::run(const Expression&, const Eigen::DefaultDevice&) [with Expression = const Eigen::TensorAssignOp<Eigen::Tensor<double, 3, 0, long int>, const Eigen::TensorCwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, const Eigen::Tensor<double, 3, 0, long int> > >]’:
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/Tensor.h:417:65:   required from ‘Eigen::Tensor<Scalar_, NumIndices_, Options_, IndexType>& Eigen::Tensor<Scalar_, NumIndices_, Options_, IndexType>::operator=(const OtherDerived&) [with OtherDerived = Eigen::TensorCwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, const Eigen::Tensor<double, 3, 0, long int> >; Scalar_ = double; int NumIndices_ = 3; int Options_ = 0; IndexType_ = long int]’
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h:845:24:   required from ‘Derived& Eigen::TensorBase<Derived, AccessLevel>::setConstant(const Scalar&) [with Derived = Eigen::Tensor<double, 3, 0, long int>; int AccessLevel = 1; Eigen::TensorBase<Derived, AccessLevel>::Scalar = double]’
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h:841:14:   required from ‘Derived& Eigen::TensorBase<Derived, AccessLevel>::setZero() [with Derived = Eigen::Tensor<double, 3, 0, long int>; int AccessLevel = 1]’
/opt/openrobots/include/pinocchio/multibody/data.hxx:131:5:   required from ‘pinocchio::DataTpl<Scalar, Options, JointCollectionTpl>::DataTpl(const Model&) [with _Scalar = double; int _Options = 0; JointCollectionTpl = pinocchio::JointCollectionDefaultTpl; pinocchio::DataTpl<Scalar, Options, JointCollectionTpl>::Model = pinocchio::ModelTpl<double>]’
cartesian_impedence_controller_simplify.cpp:18:31:   required from here
/usr/include/eigen3/unsupported/Eigen/CXX11/src/Tensor/TensorExecutor.h:61:17: warning: ignoring attributes on template argument ‘Eigen::TensorEvaluator<const Eigen::TensorAssignOp<Eigen::Tensor<double, 3, 0, long int>, const Eigen::TensorCwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, const Eigen::Tensor<double, 3, 0, long int> > >, Eigen::DefaultDevice>::PacketReturnType’ {aka ‘__vector(2) double’} [-Wignored-attributes]
       const int PacketSize = unpacket_traits<typename TensorEvaluator<Expression, DefaultDevice>::PacketReturnType>::size;
                 ^~~~~~~~~~
YaoweiFan commented 3 years ago

@jcarpent What is your compiler? If the problem related to the compiler, I think I can change a compiler.

jcarpent commented 3 years ago

I'm using Clang. But the pointer solution should work.

YaoweiFan commented 3 years ago

Thanks a lot @jcarpent

jcarpent commented 3 years ago

I will close the issue. Feel free to reopen it @YaoweiFan