Directory: | ./ |
---|---|
File: | include/crocoddyl/multibody/residuals/contact-wrench-cone.hxx |
Date: | 2025-01-16 08:47:40 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 49 | 64 | 76.6% |
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 | 175 | 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 | 175 | : Base(state, fref.get_nf() + 13, nu, fwddyn ? true : false, | |
18 | fwddyn ? true : false, true), | ||
19 | 175 | fwddyn_(fwddyn), | |
20 | 175 | update_jacobians_(true), | |
21 | 175 | id_(id), | |
22 |
6/8✓ Branch 0 taken 125 times.
✓ Branch 1 taken 50 times.
✓ Branch 2 taken 125 times.
✓ Branch 3 taken 50 times.
✓ Branch 6 taken 175 times.
✗ Branch 7 not taken.
✓ Branch 10 taken 175 times.
✗ Branch 11 not taken.
|
350 | fref_(fref) { |
23 |
1/2✗ Branch 3 not taken.
✓ Branch 4 taken 175 times.
|
175 | 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 | 175 | } | |
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 | 1 | fwddyn_(true), | |
37 | 1 | update_jacobians_(true), | |
38 | 1 | id_(id), | |
39 |
2/4✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
1 | fref_(fref) { |
40 |
1/2✗ Branch 3 not taken.
✓ Branch 4 taken 1 times.
|
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 | 356 | ResidualModelContactWrenchConeTpl< | |
50 | 356 | 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 |
2/4✓ Branch 6 taken 17585 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 17585 times.
✗ Branch 10 not taken.
|
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 |
3/4✓ Branch 0 taken 627 times.
✓ Branch 1 taken 766 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 627 times.
|
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 |
1/2✓ Branch 1 taken 19521 times.
✗ Branch 2 not taken.
|
39042 | boost::shared_ptr<ResidualDataAbstract> d = boost::allocate_shared<Data>( |
91 | 19521 | Eigen::aligned_allocator<Data>(), this, data); | |
92 |
2/2✓ Branch 0 taken 7156 times.
✓ Branch 1 taken 12365 times.
|
19521 | if (!fwddyn_) { |
93 |
1/2✓ Branch 1 taken 7156 times.
✗ Branch 2 not taken.
|
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 |
2/4✓ Branch 3 taken 7922 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 7922 times.
✗ Branch 7 not taken.
|
7922 | data->Rx.noalias() = A * df_dx; |
107 |
2/4✓ Branch 3 taken 7922 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 7922 times.
✗ Branch 7 not taken.
|
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 | ||
153 |