Program Listing for File friction-cone.hpp

Return to documentation for file (include/crocoddyl/multibody/friction-cone.hpp)

// BSD 3-Clause License
//
// Copyright (C) 2019-2025, University of Edinburgh, University of Oxford,
//                          Heriot-Watt University
// Copyright note valid unless otherwise stated in individual files.
// All rights reserved.

#ifndef CROCODDYL_MULTIBODY_FRICTION_CONE_HPP_
#define CROCODDYL_MULTIBODY_FRICTION_CONE_HPP_

#include "crocoddyl/core/utils/deprecate.hpp"
#include "crocoddyl/multibody/fwd.hpp"

namespace crocoddyl {

template <typename _Scalar>
class FrictionConeTpl {
 public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW

  typedef _Scalar Scalar;
  typedef MathBaseTpl<Scalar> MathBase;
  typedef typename MathBase::Vector3s Vector3s;
  typedef typename MathBase::Matrix3s Matrix3s;
  typedef typename MathBase::VectorXs VectorXs;
  typedef typename MathBase::MatrixXs MatrixXs;
  typedef typename MathBase::MatrixX3s MatrixX3s;
  typedef typename MathBase::Quaternions Quaternions;

  FrictionConeTpl(
      const Matrix3s& R, const Scalar mu, std::size_t nf = 4,
      const bool inner_appr = true, const Scalar min_nforce = Scalar(0.),
      const Scalar max_nforce = std::numeric_limits<Scalar>::infinity());

  FrictionConeTpl(const FrictionConeTpl<Scalar>& cone);

  explicit FrictionConeTpl();
  ~FrictionConeTpl();

  void update();
  DEPRECATED("Use update()",
             void update(const Vector3s& normal, const Scalar mu,
                         const bool inner_appr = true,
                         const Scalar min_nforce = Scalar(0.),
                         const Scalar max_nforce =
                             std::numeric_limits<Scalar>::infinity()));

  template <typename NewScalar>
  FrictionConeTpl<NewScalar> cast() const;

  const MatrixX3s& get_A() const;

  const VectorXs& get_ub() const;

  const VectorXs& get_lb() const;

  std::size_t get_nf() const;

  const Matrix3s& get_R() const;

  DEPRECATED("Use get_R.", Vector3s get_nsurf();)

  const Scalar get_mu() const;

  bool get_inner_appr() const;

  const Scalar get_min_nforce() const;

  const Scalar get_max_nforce() const;

  void set_R(const Matrix3s& R);

  DEPRECATED("Use set_R.", void set_nsurf(const Vector3s& nsurf);)

  void set_mu(const Scalar mu);

  void set_inner_appr(const bool inner_appr);

  void set_min_nforce(const Scalar min_nforce);

  void set_max_nforce(const Scalar max_nforce);

  FrictionConeTpl<Scalar>& operator=(const FrictionConeTpl<Scalar>& other);

  template <class Scalar>
  friend std::ostream& operator<<(std::ostream& os,
                                  const FrictionConeTpl<Scalar>& X);

 private:
  std::size_t nf_;
  MatrixX3s A_;
  VectorXs ub_;
  VectorXs lb_;
  Matrix3s R_;
  Scalar mu_;
  bool inner_appr_;
  Scalar min_nforce_;
  Scalar max_nforce_;
};

}  // namespace crocoddyl
/* --- Details -------------------------------------------------------------- */
/* --- Details -------------------------------------------------------------- */
/* --- Details -------------------------------------------------------------- */
#include "crocoddyl/multibody/friction-cone.hxx"

CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(crocoddyl::FrictionConeTpl)

#endif  // CROCODDYL_MULTIBODY_FRICTION_CONE_HPP_