loco-3d / crocoddyl

Crocoddyl is an optimal control library for robot control under contact sequence. Its solver is based on various efficient Differential Dynamic Programming (DDP)-like algorithms
BSD 3-Clause "New" or "Revised" License
858 stars 174 forks source link

Undefined Symbols for architecture arm64 on MacM1 when compiling custom action model #1148

Closed Flo-Wo closed 1 year ago

Flo-Wo commented 1 year ago

Hi all,

thank you for providing such an amazing package. After we achieved outstanding results in simulation with your package, we want to transfer our results to the real system and thus need a C++ implementation.

After building all the dependencies from source and then building crocoddyl 2.0 from source (which worked like a charm), I receive the following error

Undefined symbols for architecture arm64:
  "crocoddyl::Exception::Exception(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>> const&, char const*, char const*, int)", referenced from:
      crocoddyl::CostModelSumTpl<double>::calc(boost::shared_ptr<crocoddyl::CostDataSumTpl<double>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&) in ActionModel-ca09b6.o
      crocoddyl::CostModelSumTpl<double>::calcDiff(boost::shared_ptr<crocoddyl::CostDataSumTpl<double>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&) in ActionModel-ca09b6.o
      crocoddyl::DifferentialActionModelAbstractTpl<double>::quasiStatic(boost::shared_ptr<crocoddyl::DifferentialActionDataAbstractTpl<double>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0, Eigen::InnerStride<1>>, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&, unsigned long, double) in ActionModel-ca09b6.o
  "crocoddyl::Exception::~Exception()", referenced from:
      crocoddyl::CostModelSumTpl<double>::calc(boost::shared_ptr<crocoddyl::CostDataSumTpl<double>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&) in ActionModel-ca09b6.o
      crocoddyl::CostModelSumTpl<double>::calcDiff(boost::shared_ptr<crocoddyl::CostDataSumTpl<double>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&) in ActionModel-ca09b6.o
      crocoddyl::DifferentialActionModelAbstractTpl<double>::quasiStatic(boost::shared_ptr<crocoddyl::DifferentialActionDataAbstractTpl<double>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0, Eigen::InnerStride<1>>, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&, unsigned long, double) in ActionModel-ca09b6.o
  "typeinfo for crocoddyl::Exception", referenced from:
      crocoddyl::CostModelSumTpl<double>::calc(boost::shared_ptr<crocoddyl::CostDataSumTpl<double>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&) in ActionModel-ca09b6.o
      crocoddyl::CostModelSumTpl<double>::calcDiff(boost::shared_ptr<crocoddyl::CostDataSumTpl<double>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&) in ActionModel-ca09b6.o
      crocoddyl::DifferentialActionModelAbstractTpl<double>::quasiStatic(boost::shared_ptr<crocoddyl::DifferentialActionDataAbstractTpl<double>> const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0, Eigen::InnerStride<1>>, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1>> const&, unsigned long, double) in ActionModel-ca09b6.o
ld: symbol(s) not found for architecture arm64

when I try to compile the following custom model:

#include <crocoddyl/core/action-base.hpp>
#include <crocoddyl/core/actuation-base.hpp>
#include <crocoddyl/core/data-collector-base.hpp>

#include <crocoddyl/core/utils/exception.hpp>

#include <crocoddyl/core/diff-action-base.hpp>
#include <crocoddyl/core/costs/cost-sum.hpp>

#include <crocoddyl/multibody/states/multibody.hpp>

#include <pinocchio/algorithm/rnea-derivatives.hpp>
#include <pinocchio/algorithm/aba-derivatives.hpp>
#include <pinocchio/algorithm/compute-all-terms.hpp>
#include <pinocchio/algorithm/frames.hpp>
#include <pinocchio/algorithm/kinematics.hpp>
#include <pinocchio/algorithm/rnea.hpp>

#include "FrictionModel.hpp"
#include "ActionModel.hpp"

class DifferentialActionDataFrictionFwdDynamics: public crocoddyl::DifferentialActionDataAbstract {
    typedef crocoddyl::DifferentialActionDataAbstract Base;

public:
    DifferentialActionDataFrictionFwdDynamics(DifferentialActionModelFrictionFwdDynamics* const action_model):
        Base(action_model),
        pinocchio_data(pinocchio::DataTpl(action_model->pinocchio_)),
        multibody_data(
            &pinocchio_data, action_model->actuation_->createData(),
            boost::make_shared<crocoddyl::JointDataAbstract>(
                action_model->state_, action_model->actuation_, action_model->get_nu())),
        costs(action_model->costs_->createData(&multibody_data))
        // tmp_xstatic(model->get_state()->get_nx()) {
        // const std::size_t nv = model->get_state()->get_nv();
        // Fu.leftCols(nv).diagonal().setOnes();
        // multibody.joint->da_du.leftCols(nv).diagonal().setOnes();

        {
        // tmp_xstatic.setZero();
        costs->shareMemory(this);
    }

    pinocchio::DataTpl<Scalar> pinocchio_data;                  //!< Pinocchio data
    // DataCollectorJointActMultibodyTpl
    crocoddyl::DataCollectorJointActMultibody multibody_data;              //!< Multibody data
    boost::shared_ptr<crocoddyl::CostDataSum> costs;                  //!< Costs data
    // Eigen::VectorXs
    //     tmp_xstatic;  //!< State point used for computing the quasi-static input
    using Base::cost;
    using Base::Fu;
    using Base::Fx;
    using Base::Lu;
    using Base::Luu;
    using Base::Lx;
    using Base::Lxu;
    using Base::Lxx;
    using Base::r;
    using Base::xout;
};

DifferentialActionModelFrictionFwdDynamics::DifferentialActionModelFrictionFwdDynamics(
    boost::shared_ptr<crocoddyl::StateMultibody> state,
    boost::shared_ptr<crocoddyl::ActuationModelAbstract> actuation,
    boost::shared_ptr<crocoddyl::CostModelSum> costs,
    const Eigen::VectorXd& armature,
    const Eigen::VectorXd& damping,
    const Eigen::VectorXd& coulomb_friction,
    const Eigen::VectorXi& grav_comp_idxs
    )
    : crocoddyl::DifferentialActionModelAbstract(state, actuation->get_nu(), costs->get_nr()),
        actuation_(actuation),
        armature_(state->get_nv()),
        // pinocchio model and data
        pinocchio_(*state->get_pinocchio().get()),
        // friction model
        damping_(state->get_nv()),
        coulomb_friction_(state->get_nv()),
        grav_comp_idxs_(state->get_nv()),
        costs_(costs),
        // cost_data_(costs.createData(TODO: datacollector abstract)),

        // is this fine -> overwrite the internal state
        state_(state),
        // custom friction model
        friction_model_(coulomb_friction, damping) {

    if (armature.size() > 0) {
        armature_ = armature;
    }
    if (damping.size() == 0) {
        damping_.setZero();
    } else {
        damping_ = damping;
    }
    if (coulomb_friction.size() == 0) {
        coulomb_friction_.setZero();
    } else {
        coulomb_friction_ = coulomb_friction;
    }
    if (grav_comp_idxs.size() == 0) {
        grav_comp_idxs_.resize(state->get_nv());
        for (std::size_t i = 0; i < state->get_nv(); ++i) {
            grav_comp_idxs_[i] = i;
        }
    } else {
        grav_comp_idxs_ = grav_comp_idxs;
    }
}

void DifferentialActionModelFrictionFwdDynamics::calc(
    const boost::shared_ptr<DifferentialActionDataAbstract>& data,
    const Eigen::Ref<const Eigen::VectorXd>& x,
    const Eigen::Ref<const Eigen::VectorXd>& u
    ) {

    DifferentialActionDataFrictionFwdDynamics* d = static_cast<DifferentialActionDataFrictionFwdDynamics*>(data.get());
    actuation_->calc(d->multibody_data.actuation, x, u);
    Eigen::VectorXd q = x.head(state_->get_nq());
    Eigen::VectorXd v = x.tail(state_->get_nv());

    pinocchio::computeAllTerms(pinocchio_, d->pinocchio_data, q, v);
    Eigen::MatrixXd mass_matrix = d->pinocchio_data.M + Eigen::Matrix2d(armature_.asDiagonal());
    Eigen::VectorXd g = Eigen::VectorXd::Zero(d->pinocchio_data.g.size());

    g.segment(grav_comp_idxs_.minCoeff(), grav_comp_idxs_.size()) =
        d->pinocchio_data.g.segment(grav_comp_idxs_.minCoeff(), grav_comp_idxs_.size());
    data->xout = mass_matrix.ldlt().solve(u + g + friction_model_.calc(v) - d->pinocchio_data.nle);

    pinocchio::forwardKinematics(pinocchio_, d->pinocchio_data, q, v);
    pinocchio::updateFramePlacements(pinocchio_, d->pinocchio_data);

    // costs_->calc(cost_data_, x, u);
    costs_->calc(d->costs, x, u);
    d->cost = d->costs->cost;
}

void DifferentialActionModelFrictionFwdDynamics::calcDiff(
    const boost::shared_ptr<DifferentialActionDataAbstract>& data,
    const Eigen::Ref<const Eigen::VectorXd>& x,
    const Eigen::Ref<const Eigen::VectorXd>& u
    ) {
    DifferentialActionDataFrictionFwdDynamics* d = static_cast<DifferentialActionDataFrictionFwdDynamics*>(data.get());

    Eigen::VectorXd q = x.head(state_->get_nq());
    Eigen::VectorXd v = x.tail(state_->get_nv());

    Eigen::MatrixXd grav_comp_derivatives;
    pinocchio::computeGeneralizedGravityDerivatives(pinocchio_, d->pinocchio_data, q, grav_comp_derivatives);
    Eigen::MatrixXd pruned_grav_comp_derivates = Eigen::MatrixXd::Zero(grav_comp_derivatives.rows(),
                                                                       grav_comp_derivatives.cols());
    pruned_grav_comp_derivates.block(grav_comp_idxs_.minCoeff(), 0, grav_comp_idxs_.size(), grav_comp_idxs_.size()) =
        grav_comp_derivatives.block(grav_comp_idxs_.minCoeff(), 0, grav_comp_idxs_.size(), grav_comp_idxs_.size());
    // calculate 
    calc(data, x, u);

    Eigen::VectorXd dtau_dq, dtau_dv;
    Eigen::MatrixXd mass_matrix;

    pinocchio::computeRNEADerivatives(pinocchio_, d->pinocchio_data, q, v, data->xout, dtau_dq,
                                      dtau_dv, mass_matrix);
    mass_matrix += armature_.asDiagonal();
    Eigen::MatrixXd dacc_dq_rec =
        -(mass_matrix.ldlt().solve(dtau_dq - pruned_grav_comp_derivates));
    Eigen::MatrixXd dacc_dv_rec =
        -(mass_matrix.ldlt().solve(dtau_dv - friction_model_.calcDiff(v)));

    d->Fx.topRows(state_->get_nq()) = dacc_dq_rec;
    d->Fx.bottomRows(state_->get_nv()) = dacc_dv_rec;
    d->Fu = mass_matrix.inverse();
    costs_->calcDiff(d->costs, x, u);
}
void DifferentialActionModelFrictionFwdDynamics::quasiStatic(
        const boost::shared_ptr<DifferentialActionDataAbstract>& data,
        Eigen::Ref<VectorXs> u, const Eigen::Ref<const VectorXs>& x,
        const std::size_t maxIter, const float tol
      ){

      }

boost::shared_ptr<crocoddyl::DifferentialActionDataAbstract> DifferentialActionModelFrictionFwdDynamics::createData() {
    return boost::allocate_shared<DifferentialActionDataFrictionFwdDynamics>(
        Eigen::aligned_allocator<DifferentialActionDataFrictionFwdDynamics>(), this
    );
}

int main(){
    return 0;
}

I use the following command to start the compiler:

g++ action_model/ActionModel.cpp -I"/opt/homebrew/include/eigen3" -I"/opt/homebrew/opt/boost@1.76/include" --std=c++17 -o ./action_model/action_model.out

I tried it with different version, e.g. c++20, but that did not work due to some error in the boost library which does not seem to be fixed yet.

Since I am not a C++ expert, I am really grateful for your hints.

Thank you very much in advance!

nim65s commented 1 year ago

Hi,

I can't reproduce without FrictionModel.hpp & ActionModel.hpp. Could you either fix your cpp or include those files ?

Flo-Wo commented 1 year ago

Ah yes, you are perfectly right. Sorry for the inconvenience and thanks for the quick response!

FrictionModel.hpp

#ifndef  FRICTION_MODEL_HPP
#define FRICTION_MODEL_HPP

#include <Eigen/Dense>

class FrictionModel {
public:
    FrictionModel(const Eigen::Ref<const Eigen::VectorXd>& coulomb_friction,
                  const Eigen::Ref<const Eigen::VectorXd>& damping,
                  float coulomb_slope = 100.0
                  )
        : coulomb_friction_(coulomb_friction), damping_(damping), coulomb_slope_(coulomb_slope) {}

    // calculation methods
    Eigen::VectorXd calc(const Eigen::Ref<const Eigen::VectorXd>& v) const {
        return (-1) * (coulomb_friction_.array() * (coulomb_slope_ * v).array().tanh()).matrix() - v.cwiseProduct(damping_);
    }

    Eigen::MatrixXd calcDiff(const Eigen::Ref<const Eigen::VectorXd>& v) const {
        return ((-1) * coulomb_slope_ * (1 - (coulomb_slope_ * v).array().tanh().square())).matrix().asDiagonal() - damping_.asDiagonal();
    }

private:
    Eigen::VectorXd coulomb_friction_;
    Eigen::VectorXd damping_;
    float coulomb_slope_;
};
#endif  // FRICTION_MODEL_HPP

and

ActionModel.hpp

#ifndef ACTION_MODEL_HPP
#define ACTION_MODEL_HPP

#include <crocoddyl/core/action-base.hpp>
#include <crocoddyl/core/actuation-base.hpp>
#include <crocoddyl/core/data-collector-base.hpp>
#include <crocoddyl/core/utils/exception.hpp>

#include <crocoddyl/core/diff-action-base.hpp>
#include <crocoddyl/core/costs/cost-sum.hpp>

#include <crocoddyl/multibody/states/multibody.hpp>
#include <crocoddyl/multibody/data/multibody.hpp>

#include "FrictionModel.hpp"

class DifferentialActionModelFrictionFwdDynamics : public crocoddyl::DifferentialActionModelAbstract {
  public:
      DifferentialActionModelFrictionFwdDynamics(
          boost::shared_ptr<crocoddyl::StateMultibody> state,
          boost::shared_ptr<crocoddyl::ActuationModelAbstract> actuation,
          boost::shared_ptr<crocoddyl::CostModelSum> costs,
          const Eigen::VectorXd& armature = Eigen::VectorXd(),
          const Eigen::VectorXd& damping = Eigen::VectorXd(),
          const Eigen::VectorXd& coulomb_friction = Eigen::VectorXd(),
          const Eigen::VectorXi& grav_comp_idxs = Eigen::VectorXi()
      );

      void calc(const boost::shared_ptr<DifferentialActionDataAbstract>& data,
                const Eigen::Ref<const Eigen::VectorXd>& x,
                const Eigen::Ref<const Eigen::VectorXd>& u = Eigen::VectorXd());

      void calcDiff(const boost::shared_ptr<DifferentialActionDataAbstract>& data,
                    const Eigen::Ref<const Eigen::VectorXd>& x,
                    const Eigen::Ref<const Eigen::VectorXd>& u);

      // void quasiStatic(
      //   const boost::shared_ptr<DifferentialActionDataAbstract>& data,
      //   Eigen::Ref<VectorXs> u, const Eigen::Ref<const VectorXs>& x,
      //   const std::size_t maxIter, const float tol
      // );

      boost::shared_ptr<crocoddyl::DifferentialActionDataAbstract> createData();

      // make all attributes public
      boost::shared_ptr<crocoddyl::ActuationModelAbstract> actuation_;
      boost::shared_ptr<crocoddyl::StateMultibody> state_;
      boost::shared_ptr<crocoddyl::CostModelSum> costs_;
      // pinocchio part
      pinocchio::Model pinocchio_;
      // friction model
      Eigen::VectorXd armature_;
      Eigen::VectorXd damping_;
      Eigen::VectorXd coulomb_friction_;
      Eigen::VectorXi grav_comp_idxs_;
      FrictionModel friction_model_;
};
#endif  // ACTION_MODEL_HPP
cmastalli commented 1 year ago

Closing this issue due to inactivity