Line |
Branch |
Exec |
Source |
1 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
2 |
|
|
// BSD 3-Clause License |
3 |
|
|
// |
4 |
|
|
// Copyright (C) 2020-2025, 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 |
|
✗ |
ResidualModelContactWrenchConeTpl<Scalar>::ResidualModelContactWrenchConeTpl( |
15 |
|
|
std::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id, |
16 |
|
|
const WrenchCone& fref, const std::size_t nu, const bool fwddyn) |
17 |
|
✗ |
: 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 |
|
✗ |
fref_(fref) { |
23 |
|
✗ |
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 |
|
|
} |
30 |
|
|
|
31 |
|
|
template <typename Scalar> |
32 |
|
✗ |
ResidualModelContactWrenchConeTpl<Scalar>::ResidualModelContactWrenchConeTpl( |
33 |
|
|
std::shared_ptr<StateMultibody> state, const pinocchio::FrameIndex id, |
34 |
|
|
const WrenchCone& fref) |
35 |
|
✗ |
: Base(state, fref.get_nf() + 13), |
36 |
|
✗ |
fwddyn_(true), |
37 |
|
✗ |
update_jacobians_(true), |
38 |
|
✗ |
id_(id), |
39 |
|
✗ |
fref_(fref) { |
40 |
|
✗ |
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 |
|
|
} |
47 |
|
|
|
48 |
|
|
template <typename Scalar> |
49 |
|
✗ |
void ResidualModelContactWrenchConeTpl<Scalar>::calc( |
50 |
|
|
const std::shared_ptr<ResidualDataAbstract>& data, |
51 |
|
|
const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) { |
52 |
|
✗ |
Data* d = static_cast<Data*>(data.get()); |
53 |
|
|
|
54 |
|
|
// Compute the residual of the wrench cone. Note that we need to transform the |
55 |
|
|
// wrench to the contact frame |
56 |
|
✗ |
data->r.noalias() = fref_.get_A() * d->contact->f.toVector(); |
57 |
|
|
} |
58 |
|
|
|
59 |
|
|
template <typename Scalar> |
60 |
|
✗ |
void ResidualModelContactWrenchConeTpl<Scalar>::calc( |
61 |
|
|
const std::shared_ptr<ResidualDataAbstract>& data, |
62 |
|
|
const Eigen::Ref<const VectorXs>&) { |
63 |
|
✗ |
data->r.setZero(); |
64 |
|
|
} |
65 |
|
|
|
66 |
|
|
template <typename Scalar> |
67 |
|
✗ |
void ResidualModelContactWrenchConeTpl<Scalar>::calcDiff( |
68 |
|
|
const std::shared_ptr<ResidualDataAbstract>& data, |
69 |
|
|
const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) { |
70 |
|
✗ |
if (fwddyn_ || update_jacobians_) { |
71 |
|
✗ |
updateJacobians(data); |
72 |
|
|
} |
73 |
|
|
} |
74 |
|
|
|
75 |
|
|
template <typename Scalar> |
76 |
|
✗ |
void ResidualModelContactWrenchConeTpl<Scalar>::calcDiff( |
77 |
|
|
const std::shared_ptr<ResidualDataAbstract>& data, |
78 |
|
|
const Eigen::Ref<const VectorXs>&) { |
79 |
|
✗ |
data->Rx.setZero(); |
80 |
|
|
} |
81 |
|
|
|
82 |
|
|
template <typename Scalar> |
83 |
|
|
std::shared_ptr<ResidualDataAbstractTpl<Scalar> > |
84 |
|
✗ |
ResidualModelContactWrenchConeTpl<Scalar>::createData( |
85 |
|
|
DataCollectorAbstract* const data) { |
86 |
|
✗ |
std::shared_ptr<ResidualDataAbstract> d = |
87 |
|
✗ |
std::allocate_shared<Data>(Eigen::aligned_allocator<Data>(), this, data); |
88 |
|
✗ |
if (!fwddyn_) { |
89 |
|
✗ |
updateJacobians(d); |
90 |
|
|
} |
91 |
|
✗ |
return d; |
92 |
|
|
} |
93 |
|
|
|
94 |
|
|
template <typename Scalar> |
95 |
|
✗ |
void ResidualModelContactWrenchConeTpl<Scalar>::updateJacobians( |
96 |
|
|
const std::shared_ptr<ResidualDataAbstract>& data) { |
97 |
|
✗ |
Data* d = static_cast<Data*>(data.get()); |
98 |
|
|
|
99 |
|
✗ |
const MatrixXs& df_dx = d->contact->df_dx; |
100 |
|
✗ |
const MatrixXs& df_du = d->contact->df_du; |
101 |
|
✗ |
const MatrixX6s& A = fref_.get_A(); |
102 |
|
✗ |
data->Rx.noalias() = A * df_dx; |
103 |
|
✗ |
data->Ru.noalias() = A * df_du; |
104 |
|
✗ |
update_jacobians_ = false; |
105 |
|
|
} |
106 |
|
|
|
107 |
|
|
template <typename Scalar> |
108 |
|
|
template <typename NewScalar> |
109 |
|
|
ResidualModelContactWrenchConeTpl<NewScalar> |
110 |
|
✗ |
ResidualModelContactWrenchConeTpl<Scalar>::cast() const { |
111 |
|
|
typedef ResidualModelContactWrenchConeTpl<NewScalar> ReturnType; |
112 |
|
|
typedef StateMultibodyTpl<NewScalar> StateType; |
113 |
|
✗ |
ReturnType ret( |
114 |
|
✗ |
std::static_pointer_cast<StateType>(state_->template cast<NewScalar>()), |
115 |
|
✗ |
id_, fref_.template cast<NewScalar>(), nu_, fwddyn_); |
116 |
|
✗ |
return ret; |
117 |
|
|
} |
118 |
|
|
|
119 |
|
|
template <typename Scalar> |
120 |
|
✗ |
void ResidualModelContactWrenchConeTpl<Scalar>::print(std::ostream& os) const { |
121 |
|
✗ |
std::shared_ptr<StateMultibody> s = |
122 |
|
✗ |
std::static_pointer_cast<StateMultibody>(state_); |
123 |
|
✗ |
const Eigen::IOFormat fmt(2, Eigen::DontAlignCols, ", ", ";\n", "", "", "[", |
124 |
|
|
"]"); |
125 |
|
|
os << "ResidualModelContactWrenchCone {frame=" |
126 |
|
✗ |
<< s->get_pinocchio()->frames[id_].name << ", mu=" << fref_.get_mu() |
127 |
|
✗ |
<< ", box=" << fref_.get_box().transpose().format(fmt) << "}"; |
128 |
|
|
} |
129 |
|
|
|
130 |
|
|
template <typename Scalar> |
131 |
|
✗ |
bool ResidualModelContactWrenchConeTpl<Scalar>::is_fwddyn() const { |
132 |
|
✗ |
return fwddyn_; |
133 |
|
|
} |
134 |
|
|
|
135 |
|
|
template <typename Scalar> |
136 |
|
✗ |
pinocchio::FrameIndex ResidualModelContactWrenchConeTpl<Scalar>::get_id() |
137 |
|
|
const { |
138 |
|
✗ |
return id_; |
139 |
|
|
} |
140 |
|
|
|
141 |
|
|
template <typename Scalar> |
142 |
|
|
const WrenchConeTpl<Scalar>& |
143 |
|
✗ |
ResidualModelContactWrenchConeTpl<Scalar>::get_reference() const { |
144 |
|
✗ |
return fref_; |
145 |
|
|
} |
146 |
|
|
|
147 |
|
|
template <typename Scalar> |
148 |
|
✗ |
void ResidualModelContactWrenchConeTpl<Scalar>::set_id( |
149 |
|
|
const pinocchio::FrameIndex id) { |
150 |
|
✗ |
id_ = id; |
151 |
|
|
} |
152 |
|
|
|
153 |
|
|
template <typename Scalar> |
154 |
|
✗ |
void ResidualModelContactWrenchConeTpl<Scalar>::set_reference( |
155 |
|
|
const WrenchCone& reference) { |
156 |
|
✗ |
fref_ = reference; |
157 |
|
✗ |
update_jacobians_ = true; |
158 |
|
|
} |
159 |
|
|
|
160 |
|
|
} // namespace crocoddyl |
161 |
|
|
|