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.88k stars 391 forks source link

build error related to URDF class pointers #627

Closed markusgft closed 5 years ago

markusgft commented 5 years ago

Dear all, I installed the package-version of Pinocchio on a standard Ubuntu 16.04 alongside ROS kinetic. When trying to build code which uses pinocchio's URDF parser, I obtain the error shown below. I can confirm that this error occurs on multiple independent machines (tested on 3 Ubuntu installations). It seems that you already fixed it in the devel version by introducing a PINOCCHIO_ prefix, but is there any way to resolve this using the current packaged version, i.e. without re-building pinocchio devel from source? Thanks!


Errors << mg_pinocchio_test:make /home/catkin_ws/logs/mg_pinocchio_test/build.make.000.log
In file included from /opt/openrobots/include/pinocchio/parsers/urdf.hpp:25:0, from /home/catkin_ws/src/mg_pinocchio_test/src/pinocchio_test.cpp:11: /opt/openrobots/include/pinocchio/parsers/urdf/types.hpp:37:0: warning: "URDF_TYPEDEF_CLASS_POINTER" redefined

define URDF_TYPEDEF_CLASS_POINTER(Class) \

^ In file included from /usr/include/urdf_model/joint.h:44:0, from /usr/include/urdf_model/link.h:44, from /usr/include/urdf_model/model.h:42, from /opt/openrobots/include/pinocchio/parsers/urdf/types.hpp:21, from /opt/openrobots/include/pinocchio/parsers/urdf.hpp:25, from /home/catkin_ws/src/mg_pinocchio_test/src/pinocchio_test.cpp:11: /usr/include/urdf_model/types.h:44:0: note: this is the location of the previous definition

define URDF_TYPEDEF_CLASS_POINTER(Class) \

^ In file included from /opt/openrobots/include/pinocchio/parsers/urdf.hpp:25:0, from /home/catkin_ws/src/mg_pinocchio_test/src/pinocchio_test.cpp:11: /opt/openrobots/include/pinocchio/parsers/urdf/types.hpp:58:22: error: redefinition of ‘template<class T, class U> boost::shared_ptr urdf::const_pointer_cast(const boost::shared_ptr&)’ URDF_SHARED_PTR(T) const_pointer_cast(URDF_SHARED_PTR(U) const & r) ^ In file included from /usr/include/urdf_model/joint.h:44:0, from /usr/include/urdf_model/link.h:44, from /usr/include/urdf_model/model.h:42, from /opt/openrobots/include/pinocchio/parsers/urdf/types.hpp:21, from /opt/openrobots/include/pinocchio/parsers/urdf.hpp:25, from /home/catkin_ws/src/mg_pinocchio_test/src/pinocchio_test.cpp:11: /usr/include/urdf_model/types.h:74:22: note: ‘template<class T, class U> boost::shared_ptr urdf::const_pointer_cast(const boost::shared_ptr&)’ previously declared here boost::shared_ptr const_pointer_cast(boost::shared_ptr const & r) ^ In file included from /opt/openrobots/include/pinocchio/parsers/urdf.hpp:25:0, from /home/catkin_ws/src/mg_pinocchio_test/src/pinocchio_test.cpp:11: /opt/openrobots/include/pinocchio/parsers/urdf/types.hpp:68:22: error: redefinition of ‘template<class T, class U> boost::shared_ptr urdf::dynamic_pointer_cast(const boost::shared_ptr&)’ URDF_SHARED_PTR(T) dynamic_pointer_cast(URDF_SHARED_PTR(U) const & r) ^ In file included from /usr/include/urdf_model/joint.h:44:0, from /usr/include/urdf_model/link.h:44, from /usr/include/urdf_model/model.h:42, from /opt/openrobots/include/pinocchio/parsers/urdf/types.hpp:21, from /opt/openrobots/include/pinocchio/parsers/urdf.hpp:25, from /home/catkin_ws/src/mg_pinocchio_test/src/pinocchio_test.cpp:11: /usr/include/urdf_model/types.h:80:22: note: ‘template<class T, class U> boost::shared_ptr urdf::dynamic_pointer_cast(const boost::shared_ptr&)’ previously declared here boost::shared_ptr dynamic_pointer_cast(boost::shared_ptr const & r) ^ In file included from /opt/openrobots/include/pinocchio/parsers/urdf.hpp:25:0, from /home/catkin_ws/src/mg_pinocchio_test/src/pinocchio_test.cpp:11: /opt/openrobots/include/pinocchio/parsers/urdf/types.hpp:78:22: error: redefinition of ‘template<class T, class U> boost::shared_ptr urdf::static_pointer_cast(const boost::shared_ptr&)’ URDF_SHARED_PTR(T) static_pointer_cast(URDF_SHARED_PTR(U) const & r) ^ In file included from /usr/include/urdf_model/joint.h:44:0, from /usr/include/urdf_model/link.h:44, from /usr/include/urdf_model/model.h:42, from /opt/openrobots/include/pinocchio/parsers/urdf/types.hpp:21, from /opt/openrobots/include/pinocchio/parsers/urdf.hpp:25, from /home/catkin_ws/src/mg_pinocchio_test/src/pinocchio_test.cpp:11: /usr/include/urdf_model/types.h:86:22: note: ‘template<class T, class U> boost::shared_ptr urdf::static_pointer_cast(const boost::shared_ptr&)’ previously declared here boost::shared_ptr static_pointer_cast(boost::shared_ptr const & r) ^ make[2]: [CMakeFiles/pinocchio_test.dir/src/pinocchio_test.cpp.o] Error 1 make[1]: [CMakeFiles/pinocchio_test.dir/all] Error 2 make: *** [all] Error 2 cd /home/catkin_ws/build/mg_pinocchio_test; catkin build --get-env mg_pinocchio_test | catkin env -si /usr/bin/make --jobserver-fds=6,7 -j; cd -


And here is the original code:


#include "pinocchio/spatial/se3.hpp"
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/multibody/data.hpp"
#include "pinocchio/algorithm/jacobian.hpp"
#include "pinocchio/algorithm/dynamics.hpp"
#include "pinocchio/algorithm/frames.hpp"
#include "pinocchio/algorithm/rnea.hpp"
#include "pinocchio/parsers/sample-models.hpp"
#include "pinocchio/utils/timer.hpp"
#include "pinocchio/parsers/urdf.hpp"
#include <iterator>

using namespace Eigen;

class PinocchioTest
{
public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW

  PinocchioTest(): model(), data(model){}

  bool loadFromURDF(const std::string fileName, const bool verbose = true)
  {
    std::cout << "attempting to load arm model" << std::endl;
    se3::urdf::buildModel(fileName, model, verbose);
    data = se3::Data(model);

    if (verbose)
    {
      // looking at the model properties
      std::cout << "the model has " << model.njoints << " joints " << std::endl;
      std::cout << "the joint names are: ";
      for (size_t i = 0; i < model.names.size(); i++)
      {
        std::cout << "  " << model.names[i];
      }
      std::cout << std::endl;
      std::cout << "the model has " << model.nframes << " frames " << std::endl;
      std::cout << "the model has " << model.nbodies << " bodies " << std::endl;
    }
    return true;
  }

  void testForwardKinematics(const VectorXd q, const std::string frameName)
  {
    // run forward kinematics and update positions for all frames (todo couldalso just be for one frame)
    se3::framesForwardKinematics(model, data, q);

    // query result of the forward kinematics end-effector flange
    if (model.existFrame(frameName))
    {
      size_t frame_id = model.getFrameId(frameName);
      std::cout << "frame id is " << frame_id << std::endl;
      Eigen::Vector3d pos = data.oMf[frame_id].translation_impl(); // could also get total hom transform
      Eigen::Matrix3d rot = data.oMf[frame_id].rotation_impl();
      std::cout << "forward kinematics resulting position: " << std::endl
                << pos << std::endl;
      std::cout << "forward kinematics resulting rotation: " << std::endl
                << rot << std::endl;
    }
    // todo think about returning pose or hom tansform
  }

  void testEEVelocities(VectorXd q, VectorXd v, const std::string frameName)
  {

    se3::forwardKinematics(model, data, q, v);
    se3::Motion frame_v;
    getFrameVelocity(model, data, model.getFrameId(frameName), frame_v);
    std::cout << "local (!) velocity for frame " << model.getFrameId(frameName) << std::endl
              << frame_v << std::endl
              << std::endl;
  }

  Eigen::MatrixXd evaluateJacobian(VectorXd q, const std::string frameName)
  {
    // these two are preliminaries to the jacobian eval
    se3::computeJointJacobians(model, data, q);
    se3::framesForwardKinematics(model, data, q);

    se3::Data::Matrix6x J;
    J.resize(6, model.nv);
    se3::getFrameJacobian<se3::ReferenceFrame::WORLD>(model, data, model.getFrameId(frameName), J);
    return J;
  }

  const VectorXd computeForwardDynamics(VectorXd q, VectorXd v, VectorXd tau)
  {
    double damping = 0.0;
    bool updateKinematics = true;
    Eigen::MatrixXd J(0, model.nv);
    Eigen::VectorXd gamma;

    se3::forwardDynamics(model, data, q, v, tau, J, gamma, damping, updateKinematics);
    return data.ddq;
  }

  const VectorXd computeGravityCompensation(VectorXd q)
  {
    se3::computeGeneralizedGravity(model, data, q);
    return data.g;
  }

  const VectorXd computeInverseDynamics(VectorXd q, VectorXd v, VectorXd a)
  {
    // evaluate the inverse dynamics (no external forces)
    se3::rnea(model, data, q, v, a);
    return data.tau;
  }

private:
  se3::Model model;
  se3::Data data;
};

int
main(int argc, char const *argv[])
{
  const std::string filename = "/home/samplemodel.urdf";

  PinocchioTest test;
  test.loadFromURDF(filename, true);

  VectorXd q(7);
  q.setRandom();
  VectorXd v(7);
  v.setRandom();
  VectorXd tau(7);
  tau.setRandom();

  const std::string targetFrame("arm_link8");

  test.testForwardKinematics(q, targetFrame);

  test.testEEVelocities(q, v, targetFrame);

  std::cout << " The jacobian w.r.t. the world frame ... " << std::endl
            << test.evaluateJacobian(q, targetFrame) << std::endl
            << std::endl;

  std::cout << " the resulting acceleration " << std::endl
            << test.computeForwardDynamics(q, v, tau) << std::endl
            << std::endl;

  std::cout << " the generalized gravity vector " << std::endl
            << test.computeGravityCompensation(q) << std::endl
            << std::endl;

  Eigen::VectorXd a(7);
  a.setConstant(0.0);
  std::cout << " the inverse dynamics torque " << std::endl
            << test.computeInverseDynamics(q, v, a) << std::endl
            << std::endl;

  return 0;
}
jcarpent commented 5 years ago

Hi @markusgft. Good to see you here.

I think your bug is coming from the fact that you did not compile the code with the right flags. Mainly, the definition of additional macro to use the correct of URDF pointers according to the version of urdfdom.

You can get these flags through the line: pkg-config --cflags pinocchio

Hope this answer will be helpful.

markusgft commented 5 years ago

Dear @jcarpent, thanks a lot for your quick reply, I really appreciate it! Adding the definition URDFDOM_TYPEDEF_SHARED_PTR actually resolved the problem and the example now builds successfully. Thanks again!

jcarpent commented 5 years ago

@markusgft You're welcome. It was a pleasure!