Directory: | ./ |
---|---|
File: | include/crocoddyl/core/residuals/joint-acceleration.hxx |
Date: | 2025-01-16 08:47:40 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 28 | 39 | 71.8% |
Branches: | 9 | 82 | 11.0% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | /////////////////////////////////////////////////////////////////////////////// | ||
2 | // BSD 3-Clause License | ||
3 | // | ||
4 | // Copyright (C) 2023, Heriot-Watt University | ||
5 | // Copyright note valid unless otherwise stated in individual files. | ||
6 | // All rights reserved. | ||
7 | /////////////////////////////////////////////////////////////////////////////// | ||
8 | |||
9 | #include "crocoddyl/core/residuals/joint-acceleration.hpp" | ||
10 | #include "crocoddyl/core/utils/exception.hpp" | ||
11 | |||
12 | namespace crocoddyl { | ||
13 | |||
14 | template <typename Scalar> | ||
15 | ✗ | ResidualModelJointAccelerationTpl<Scalar>::ResidualModelJointAccelerationTpl( | |
16 | boost::shared_ptr<StateAbstract> state, const VectorXs& aref, | ||
17 | const std::size_t nu) | ||
18 | ✗ | : Base(state, state->get_nv(), nu, true, true, true), aref_(aref) { | |
19 | ✗ | if (static_cast<std::size_t>(aref_.size()) != state->get_nv()) { | |
20 | ✗ | throw_pretty( | |
21 | "Invalid argument: " << "aref has wrong dimension (it should be " + | ||
22 | std::to_string(state->get_nv()) + ")"); | ||
23 | } | ||
24 | } | ||
25 | |||
26 | template <typename Scalar> | ||
27 | ✗ | ResidualModelJointAccelerationTpl<Scalar>::ResidualModelJointAccelerationTpl( | |
28 | boost::shared_ptr<StateAbstract> state, const VectorXs& aref) | ||
29 | : Base(state, state->get_nv(), state->get_nv(), true, true, true), | ||
30 | ✗ | aref_(aref) { | |
31 | ✗ | if (static_cast<std::size_t>(aref_.size()) != state->get_nv()) { | |
32 | ✗ | throw_pretty( | |
33 | "Invalid argument: " << "aref has wrong dimension (it should be " + | ||
34 | std::to_string(state->get_nv()) + ")"); | ||
35 | } | ||
36 | } | ||
37 | |||
38 | template <typename Scalar> | ||
39 | 150 | ResidualModelJointAccelerationTpl<Scalar>::ResidualModelJointAccelerationTpl( | |
40 | boost::shared_ptr<StateAbstract> state, const std::size_t nu) | ||
41 | : Base(state, state->get_nv(), nu, true, true, true), | ||
42 |
3/6✓ Branch 4 taken 150 times.
✗ Branch 5 not taken.
✓ Branch 10 taken 150 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 150 times.
✗ Branch 14 not taken.
|
150 | aref_(VectorXs::Zero(state->get_nv())) {} |
43 | |||
44 | template <typename Scalar> | ||
45 | 1 | ResidualModelJointAccelerationTpl<Scalar>::ResidualModelJointAccelerationTpl( | |
46 | boost::shared_ptr<StateAbstract> state) | ||
47 | : Base(state, state->get_nv(), state->get_nv(), true, true, true), | ||
48 |
3/6✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
|
1 | aref_(VectorXs::Zero(state->get_nv())) {} |
49 | |||
50 | template <typename Scalar> | ||
51 | 306 | ResidualModelJointAccelerationTpl< | |
52 | 306 | Scalar>::~ResidualModelJointAccelerationTpl() {} | |
53 | |||
54 | template <typename Scalar> | ||
55 | 7040 | void ResidualModelJointAccelerationTpl<Scalar>::calc( | |
56 | const boost::shared_ptr<ResidualDataAbstract>& data, | ||
57 | const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) { | ||
58 | 7040 | Data* d = static_cast<Data*>(data.get()); | |
59 |
1/2✓ Branch 4 taken 7040 times.
✗ Branch 5 not taken.
|
7040 | data->r = d->joint->a - aref_; |
60 | 7040 | } | |
61 | |||
62 | template <typename Scalar> | ||
63 | 571 | void ResidualModelJointAccelerationTpl<Scalar>::calc( | |
64 | const boost::shared_ptr<ResidualDataAbstract>& data, | ||
65 | const Eigen::Ref<const VectorXs>&) { | ||
66 | 571 | data->r.setZero(); | |
67 | 571 | } | |
68 | |||
69 | template <typename Scalar> | ||
70 | 1947 | void ResidualModelJointAccelerationTpl<Scalar>::calcDiff( | |
71 | const boost::shared_ptr<ResidualDataAbstract>& data, | ||
72 | const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) { | ||
73 | 1947 | Data* d = static_cast<Data*>(data.get()); | |
74 | 1947 | data->Rx = d->joint->da_dx; | |
75 | 1947 | data->Ru = d->joint->da_du; | |
76 | 1947 | } | |
77 | |||
78 | template <typename Scalar> | ||
79 | boost::shared_ptr<ResidualDataAbstractTpl<Scalar> > | ||
80 | 9793 | ResidualModelJointAccelerationTpl<Scalar>::createData( | |
81 | DataCollectorAbstract* const data) { | ||
82 |
1/2✓ Branch 1 taken 9793 times.
✗ Branch 2 not taken.
|
19586 | boost::shared_ptr<ResidualDataAbstract> d = boost::allocate_shared<Data>( |
83 | 9793 | Eigen::aligned_allocator<Data>(), this, data); | |
84 | 9793 | return d; | |
85 | } | ||
86 | |||
87 | template <typename Scalar> | ||
88 | ✗ | void ResidualModelJointAccelerationTpl<Scalar>::print(std::ostream& os) const { | |
89 | ✗ | os << "ResidualModelJointAcceleration"; | |
90 | } | ||
91 | |||
92 | template <typename Scalar> | ||
93 | const typename MathBaseTpl<Scalar>::VectorXs& | ||
94 | 1 | ResidualModelJointAccelerationTpl<Scalar>::get_reference() const { | |
95 | 1 | return aref_; | |
96 | } | ||
97 | |||
98 | template <typename Scalar> | ||
99 | 1 | void ResidualModelJointAccelerationTpl<Scalar>::set_reference( | |
100 | const VectorXs& reference) { | ||
101 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 1 times.
|
1 | if (static_cast<std::size_t>(reference.size()) != nr_) { |
102 | ✗ | throw_pretty( | |
103 | "Invalid argument: " | ||
104 | << "the generalized-acceleration reference has wrong dimension (" | ||
105 | << reference.size() | ||
106 | << " provided - it should be " + std::to_string(nr_) + ")") | ||
107 | } | ||
108 | 1 | aref_ = reference; | |
109 | 1 | } | |
110 | |||
111 | } // namespace crocoddyl | ||
112 |