GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: include/crocoddyl/multibody/residuals/contact-wrench-cone.hxx Lines: 42 57 73.7 %
Date: 2024-02-13 11:12:33 Branches: 23 90 25.6 %

Line Branch Exec Source
1
///////////////////////////////////////////////////////////////////////////////
2
// BSD 3-Clause License
3
//
4
// Copyright (C) 2020-2023, University of Edinburgh, Heriot-Watt University
5
// Copyright note valid unless otherwise stated in individual files.
6
// All rights reserved.
7
///////////////////////////////////////////////////////////////////////////////
8
9
#include "crocoddyl/multibody/residuals/contact-wrench-cone.hpp"
10
11
namespace crocoddyl {
12
13
template <typename Scalar>
14
173
ResidualModelContactWrenchConeTpl<Scalar>::ResidualModelContactWrenchConeTpl(
15
    boost::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id,
16
    const WrenchCone& fref, const std::size_t nu, const bool fwddyn)
17
173
    : Base(state, fref.get_nf() + 13, nu, fwddyn ? true : false,
18
           fwddyn ? true : false, true),
19
      fwddyn_(fwddyn),
20
      update_jacobians_(true),
21
      id_(id),
22


346
      fref_(fref) {
23
173
  if (static_cast<pinocchio::FrameIndex>(state->get_pinocchio()->nframes) <=
24
      id) {
25
    throw_pretty(
26
        "Invalid argument: "
27
        << "the frame index is wrong (it does not exist in the robot)");
28
  }
29
173
}
30
31
template <typename Scalar>
32
1
ResidualModelContactWrenchConeTpl<Scalar>::ResidualModelContactWrenchConeTpl(
33
    boost::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id,
34
    const WrenchCone& fref)
35
1
    : Base(state, fref.get_nf() + 13),
36
      fwddyn_(true),
37
      update_jacobians_(true),
38
      id_(id),
39

1
      fref_(fref) {
40
1
  if (static_cast<pinocchio::FrameIndex>(state->get_pinocchio()->nframes) <=
41
      id) {
42
    throw_pretty(
43
        "Invalid argument: "
44
        << "the frame index is wrong (it does not exist in the robot)");
45
  }
46
1
}
47
48
template <typename Scalar>
49
352
ResidualModelContactWrenchConeTpl<
50
352
    Scalar>::~ResidualModelContactWrenchConeTpl() {}
51
52
template <typename Scalar>
53
17585
void ResidualModelContactWrenchConeTpl<Scalar>::calc(
54
    const boost::shared_ptr<ResidualDataAbstract>& data,
55
    const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) {
56
17585
  Data* d = static_cast<Data*>(data.get());
57
58
  // Compute the residual of the wrench cone. Note that we need to transform the
59
  // wrench to the contact frame
60

17585
  data->r.noalias() = fref_.get_A() * d->contact->f.toVector();
61
17585
}
62
63
template <typename Scalar>
64
5872
void ResidualModelContactWrenchConeTpl<Scalar>::calc(
65
    const boost::shared_ptr<ResidualDataAbstract>& data,
66
    const Eigen::Ref<const VectorXs>&) {
67
5872
  data->r.setZero();
68
5872
}
69
70
template <typename Scalar>
71
1393
void ResidualModelContactWrenchConeTpl<Scalar>::calcDiff(
72
    const boost::shared_ptr<ResidualDataAbstract>& data,
73
    const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) {
74

1393
  if (fwddyn_ || update_jacobians_) {
75
766
    updateJacobians(data);
76
  }
77
1393
}
78
79
template <typename Scalar>
80
91
void ResidualModelContactWrenchConeTpl<Scalar>::calcDiff(
81
    const boost::shared_ptr<ResidualDataAbstract>& data,
82
    const Eigen::Ref<const VectorXs>&) {
83
91
  data->Rx.setZero();
84
91
}
85
86
template <typename Scalar>
87
boost::shared_ptr<ResidualDataAbstractTpl<Scalar> >
88
19521
ResidualModelContactWrenchConeTpl<Scalar>::createData(
89
    DataCollectorAbstract* const data) {
90
39042
  boost::shared_ptr<ResidualDataAbstract> d = boost::allocate_shared<Data>(
91
      Eigen::aligned_allocator<Data>(), this, data);
92
19521
  if (!fwddyn_) {
93
7156
    updateJacobians(d);
94
  }
95
19521
  return d;
96
}
97
98
template <typename Scalar>
99
7922
void ResidualModelContactWrenchConeTpl<Scalar>::updateJacobians(
100
    const boost::shared_ptr<ResidualDataAbstract>& data) {
101
7922
  Data* d = static_cast<Data*>(data.get());
102
103
7922
  const MatrixXs& df_dx = d->contact->df_dx;
104
7922
  const MatrixXs& df_du = d->contact->df_du;
105
7922
  const MatrixX6s& A = fref_.get_A();
106

7922
  data->Rx.noalias() = A * df_dx;
107

7922
  data->Ru.noalias() = A * df_du;
108
7922
  update_jacobians_ = false;
109
7922
}
110
111
template <typename Scalar>
112
void ResidualModelContactWrenchConeTpl<Scalar>::print(std::ostream& os) const {
113
  boost::shared_ptr<StateMultibody> s =
114
      boost::static_pointer_cast<StateMultibody>(state_);
115
  const Eigen::IOFormat fmt(2, Eigen::DontAlignCols, ", ", ";\n", "", "", "[",
116
                            "]");
117
  os << "ResidualModelContactWrenchCone {frame="
118
     << s->get_pinocchio()->frames[id_].name << ", mu=" << fref_.get_mu()
119
     << ", box=" << fref_.get_box().transpose().format(fmt) << "}";
120
}
121
122
template <typename Scalar>
123
bool ResidualModelContactWrenchConeTpl<Scalar>::is_fwddyn() const {
124
  return fwddyn_;
125
}
126
127
template <typename Scalar>
128
19521
pinocchio::FrameIndex ResidualModelContactWrenchConeTpl<Scalar>::get_id()
129
    const {
130
19521
  return id_;
131
}
132
133
template <typename Scalar>
134
const WrenchConeTpl<Scalar>&
135
ResidualModelContactWrenchConeTpl<Scalar>::get_reference() const {
136
  return fref_;
137
}
138
139
template <typename Scalar>
140
void ResidualModelContactWrenchConeTpl<Scalar>::set_id(
141
    const pinocchio::FrameIndex id) {
142
  id_ = id;
143
}
144
145
template <typename Scalar>
146
void ResidualModelContactWrenchConeTpl<Scalar>::set_reference(
147
    const WrenchCone& reference) {
148
  fref_ = reference;
149
  update_jacobians_ = true;
150
}
151
152
}  // namespace crocoddyl