GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: include/crocoddyl/core/residuals/joint-acceleration.hpp Lines: 6 10 60.0 %
Date: 2024-02-13 11:12:33 Branches: 2 12 16.7 %

Line Branch Exec Source
1
///////////////////////////////////////////////////////////////////////////////
2
// BSD 3-Clause License
3
//
4
// Copyright (C) 2022-2023, Heriot-Watt University
5
// Copyright note valid unless otherwise stated in individual files.
6
// All rights reserved.
7
///////////////////////////////////////////////////////////////////////////////
8
9
#ifndef CROCODDYL_CORE_RESIDUALS_JOINT_ACCELERATION_HPP_
10
#define CROCODDYL_CORE_RESIDUALS_JOINT_ACCELERATION_HPP_
11
12
#include "crocoddyl/core/actuation-base.hpp"
13
#include "crocoddyl/core/data/joint.hpp"
14
#include "crocoddyl/core/fwd.hpp"
15
#include "crocoddyl/core/residual-base.hpp"
16
17
namespace crocoddyl {
18
19
/**
20
 * @brief Define a joint-acceleration residual
21
 *
22
 * This residual function is defined as
23
 * \f$\mathbf{r}=\mathbf{u}-\mathbf{u}^*\f$, where
24
 * \f$\mathbf{u},\mathbf{u}^*\in~\mathbb{R}^{nu}\f$ are the current and
25
 * reference joint acceleration, respectively. Note that the dimension of the
26
 * residual vector is obtained from `StateAbstract::nv`, as it represents the
27
 * generalized acceleration.
28
 *
29
 * Both residual and residual Jacobians are computed analytically.
30
 *
31
 * As described in ResidualModelAbstractTpl(), the residual value and its
32
 * Jacobians are calculated by `calc` and `calcDiff`, respectively.
33
 *
34
 * \sa `ResidualModelAbstractTpl`, `calc()`, `calcDiff()`, `createData()`
35
 */
36
template <typename _Scalar>
37
class ResidualModelJointAccelerationTpl
38
    : public ResidualModelAbstractTpl<_Scalar> {
39
 public:
40
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
41
42
  typedef _Scalar Scalar;
43
  typedef MathBaseTpl<Scalar> MathBase;
44
  typedef ResidualModelAbstractTpl<Scalar> Base;
45
  typedef ResidualDataJointAccelerationTpl<Scalar> Data;
46
  typedef ResidualDataAbstractTpl<Scalar> ResidualDataAbstract;
47
  typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
48
  typedef StateAbstractTpl<Scalar> StateAbstract;
49
  typedef ActuationModelAbstractTpl<Scalar> ActuationModelAbstract;
50
  typedef typename MathBase::VectorXs VectorXs;
51
  typedef typename MathBase::MatrixXs MatrixXs;
52
53
  /**
54
   * @brief Initialize the joint-acceleration residual model
55
   *
56
   * @param[in] state       State description
57
   * @param[in] aref        Reference joint acceleration
58
   * @param[in] nu          Dimension of the control vector
59
   */
60
  ResidualModelJointAccelerationTpl(boost::shared_ptr<StateAbstract> state,
61
                                    const VectorXs& aref, const std::size_t nu);
62
63
  /**
64
   * @brief Initialize the joint-acceleration residual model
65
   *
66
   * The default `nu` value is obtained from `StateAbstractTpl::get_nv()`.
67
   *
68
   * @param[in] state       State description
69
   * @param[in] aref        Reference joint acceleration
70
   */
71
  ResidualModelJointAccelerationTpl(boost::shared_ptr<StateAbstract> state,
72
                                    const VectorXs& aref);
73
74
  /**
75
   * @brief Initialize the joint-acceleration residual model
76
   *
77
   * The default reference joint acceleration is obtained from
78
   * `MathBaseTpl<>::VectorXs::Zero(state->get_nv())`.
79
   *
80
   * @param[in] state       State description
81
   * @param[in] nu          Dimension of the control vector
82
   */
83
  ResidualModelJointAccelerationTpl(boost::shared_ptr<StateAbstract> state,
84
                                    const std::size_t nu);
85
86
  /**
87
   * @brief Initialize the joint-acceleration residual model
88
   *
89
   * The default reference joint acceleration is obtained from
90
   * `MathBaseTpl<>::VectorXs::Zero(state->get_nv())`. The default `nu` value is
91
   * obtained from `StateAbstractTpl::get_nv()`.
92
   *
93
   * @param[in] state       State description
94
   */
95
  ResidualModelJointAccelerationTpl(boost::shared_ptr<StateAbstract> state);
96
97
  virtual ~ResidualModelJointAccelerationTpl();
98
99
  /**
100
   * @brief Compute the joint-acceleration residual
101
   *
102
   * @param[in] data  Joint-acceleration residual data
103
   * @param[in] x     State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
104
   * @param[in] u     Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
105
   */
106
  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
107
                    const Eigen::Ref<const VectorXs>& x,
108
                    const Eigen::Ref<const VectorXs>& u);
109
110
  /**
111
   * @brief @copydoc Base::calc(const boost::shared_ptr<ResidualDataAbstract>&
112
   * data, const Eigen::Ref<const VectorXs>& x)
113
   */
114
  virtual void calc(const boost::shared_ptr<ResidualDataAbstract>& data,
115
                    const Eigen::Ref<const VectorXs>& x);
116
117
  /**
118
   * @brief Compute the derivatives of the joint-acceleration residual
119
   *
120
   * @param[in] data  Joint-acceleration residual data
121
   * @param[in] x     State point \f$\mathbf{x}\in\mathbb{R}^{ndx}\f$
122
   * @param[in] u     Control input \f$\mathbf{u}\in\mathbb{R}^{nu}\f$
123
   */
124
  virtual void calcDiff(const boost::shared_ptr<ResidualDataAbstract>& data,
125
                        const Eigen::Ref<const VectorXs>& x,
126
                        const Eigen::Ref<const VectorXs>& u);
127
128
  /**
129
   * @brief Create the joint-acceleration residual data
130
   */
131
  virtual boost::shared_ptr<ResidualDataAbstract> createData(
132
      DataCollectorAbstract* const data);
133
134
  /**
135
   * @brief Return the reference joint-acceleration vector
136
   */
137
  const VectorXs& get_reference() const;
138
139
  /**
140
   * @brief Modify the reference joint-acceleration vector
141
   */
142
  void set_reference(const VectorXs& reference);
143
144
  /**
145
   * @brief Print relevant information of the joint-acceleration residual
146
   *
147
   * @param[out] os  Output stream object
148
   */
149
  virtual void print(std::ostream& os) const;
150
151
 protected:
152
  using Base::nr_;
153
  using Base::nu_;
154
  using Base::state_;
155
156
 private:
157
  VectorXs aref_;  //!< Reference joint-acceleration input
158
};
159
160
template <typename _Scalar>
161
struct ResidualDataJointAccelerationTpl
162
    : public ResidualDataAbstractTpl<_Scalar> {
163
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
164
165
  typedef _Scalar Scalar;
166
  typedef MathBaseTpl<Scalar> MathBase;
167
  typedef ResidualDataAbstractTpl<Scalar> Base;
168
  typedef DataCollectorAbstractTpl<Scalar> DataCollectorAbstract;
169
170
  template <template <typename Scalar> class Model>
171
9793
  ResidualDataJointAccelerationTpl(Model<Scalar>* const model,
172
                                   DataCollectorAbstract* const data)
173
9793
      : Base(model, data) {
174
    // Check that proper shared data has been passed
175
    DataCollectorJointTpl<Scalar>* d =
176
9793
        dynamic_cast<DataCollectorJointTpl<Scalar>*>(shared);
177
9793
    if (d == nullptr) {
178
      throw_pretty(
179
          "Invalid argument: the shared data should be derived from "
180
          "DataCollectorJoint");
181
    }
182
9793
    joint = d->joint;
183
9793
  }
184
185
  boost::shared_ptr<JointDataAbstractTpl<Scalar> > joint;  //!< Joint data
186
  using Base::r;
187
  using Base::Ru;
188
  using Base::Rx;
189
  using Base::shared;
190
};
191
192
}  // namespace crocoddyl
193
194
/* --- Details -------------------------------------------------------------- */
195
/* --- Details -------------------------------------------------------------- */
196
/* --- Details -------------------------------------------------------------- */
197
#include "crocoddyl/core/residuals/joint-acceleration.hxx"
198
199
#endif  // CROCODDYL_CORE_RESIDUALS_JOINT_ACCELERATION_HPP_