GCC Code Coverage Report


Directory: ./
File: include/quadruped-walkgen/quadruped_step.hpp
Date: 2024-12-02 00:24:10
Exec Total Coverage
Lines: 0 2 0.0%
Branches: 0 0 -%

Line Branch Exec Source
1 #ifndef __quadruped_walkgen_quadruped_step_hpp__
2 #define __quadruped_walkgen_quadruped_step_hpp__
3 #include <stdexcept>
4
5 #include "crocoddyl/core/action-base.hpp"
6 #include "crocoddyl/core/fwd.hpp"
7 #include "crocoddyl/core/states/euclidean.hpp"
8 #include "crocoddyl/core/utils/timer.hpp"
9 #include "crocoddyl/multibody/friction-cone.hpp"
10
11 namespace quadruped_walkgen {
12 template <typename _Scalar>
13 class ActionModelQuadrupedStepTpl
14 : public crocoddyl::ActionModelAbstractTpl<_Scalar> {
15 public:
16 typedef _Scalar Scalar;
17 typedef crocoddyl::ActionDataAbstractTpl<Scalar> ActionDataAbstract;
18 typedef crocoddyl::ActionModelAbstractTpl<Scalar> Base;
19 typedef crocoddyl::MathBaseTpl<Scalar> MathBase;
20
21 ActionModelQuadrupedStepTpl();
22 ~ActionModelQuadrupedStepTpl();
23
24 virtual void calc(const boost::shared_ptr<ActionDataAbstract>& data,
25 const Eigen::Ref<const typename MathBase::VectorXs>& x,
26 const Eigen::Ref<const typename MathBase::VectorXs>& u);
27 virtual void calcDiff(const boost::shared_ptr<ActionDataAbstract>& data,
28 const Eigen::Ref<const typename MathBase::VectorXs>& x,
29 const Eigen::Ref<const typename MathBase::VectorXs>& u);
30 virtual boost::shared_ptr<ActionDataAbstract> createData();
31
32 // Get and Set weights vectors : state , force & friction cone :
33 const typename Eigen::Matrix<Scalar, 12, 1>& get_state_weights() const;
34 void set_state_weights(const typename MathBase::VectorXs& weights);
35
36 const typename Eigen::Matrix<Scalar, 8, 1>& get_step_weights() const;
37 void set_step_weights(const typename MathBase::VectorXs& weights);
38
39 const typename Eigen::Matrix<Scalar, 8, 1>& get_heuristic_weights() const;
40 void set_heuristic_weights(const typename MathBase::VectorXs& weights);
41
42 // Update the model depending if the foot in contact with the ground
43 // or the new lever arms
44 void update_model(
45 const Eigen::Ref<const typename MathBase::MatrixXs>& l_feet,
46 const Eigen::Ref<const typename MathBase::MatrixXs>& xref,
47 const Eigen::Ref<const typename MathBase::VectorXs>& S,
48 const Eigen::Ref<const typename MathBase::MatrixXs>& position,
49 const Eigen::Ref<const typename MathBase::MatrixXs>& velocity,
50 const Eigen::Ref<const typename MathBase::MatrixXs>& acceleration,
51 const Eigen::Ref<const typename MathBase::MatrixXs>& jerk,
52 const Eigen::Ref<const typename MathBase::MatrixXs>& oRh,
53 const Eigen::Ref<const typename MathBase::MatrixXs>& oTh,
54 const Scalar& delta_T);
55
56 const bool& get_symmetry_term() const;
57 void set_symmetry_term(const bool& sym_term);
58
59 const bool& get_centrifugal_term() const;
60 void set_centrifugal_term(const bool& cent_term);
61
62 const Scalar& get_T_gait() const;
63 void set_T_gait(const Scalar& T_gait_);
64
65 const bool& get_acc_activated() const;
66 void set_acc_activated(const bool& is_activated);
67
68 const typename Eigen::Matrix<Scalar, 2, 1>& get_acc_lim() const;
69 void set_acc_lim(const typename MathBase::VectorXs& acceleration_lim_);
70
71 const Scalar& get_acc_weight() const;
72 void set_acc_weight(const Scalar& weight_);
73
74 const bool& get_vel_activated() const;
75 void set_vel_activated(const bool& is_activated);
76
77 const typename Eigen::Matrix<Scalar, 2, 1>& get_vel_lim() const;
78 void set_vel_lim(const typename MathBase::VectorXs& velocity_lim_);
79
80 const Scalar& get_vel_weight() const;
81 void set_vel_weight(const Scalar& weight_);
82
83 void set_sample_feet_traj(const int& n_sample);
84
85 const bool& get_jerk_activated() const;
86 void set_jerk_activated(const bool& is_activated);
87
88 const Scalar& get_jerk_weight() const;
89 void set_jerk_weight(const Scalar& weight_);
90
91 protected:
92 using Base::has_control_limits_; //!< Indicates whether any of the control
93 //!< limits
94 using Base::nr_; //!< Dimension of the cost residual
95 using Base::nu_; //!< Control dimension
96 using Base::state_; //!< Model of the state
97 using Base::u_lb_; //!< Lower control limits
98 using Base::u_ub_; //!< Upper control limits
99 using Base::unone_; //!< Neutral state
100
101 private:
102 Scalar T_gait;
103 bool centrifugal_term;
104 bool symmetry_term;
105
106 typename Eigen::Matrix<Scalar, 12, 1> state_weights_;
107 typename Eigen::Matrix<Scalar, 8, 1> step_weights_;
108 typename Eigen::Matrix<Scalar, 8, 1> heuristic_weights_;
109 typename MathBase::Matrix3s R_tmp;
110
111 typename Eigen::Matrix<Scalar, 8, 8> B;
112
113 typename MathBase::MatrixXs xref_;
114 typename Eigen::Matrix<Scalar, 8, 1> pheuristic_;
115
116 // typename Eigen::Matrix<Scalar, 2, 4> pshoulder_0;
117 // typename Eigen::Matrix<Scalar, 2, 4> pshoulder_tmp;
118 // typename Eigen::Matrix<Scalar, 3, 1> pcentrifugal_tmp;
119 // typename Eigen::Matrix<Scalar, 3, 1> pcentrifugal_tmp_1;
120 // typename Eigen::Matrix<Scalar, 3, 1> pcentrifugal_tmp_2;
121
122 // Cost on the acceleration of the feet :
123 int N_sampling;
124 bool is_acc_activated_; // Boolean to activate the cost on the acceleration
125 // of the feet
126 Scalar acc_weight_; // Weight on the acceleration cost
127 typename Eigen::Matrix<Scalar, 2, 1>
128 acc_lim_; // Maximum acceleration allowed on x and y axis
129 typename Eigen::Matrix<Scalar, 4, 1> S_; // Containing the moving feet
130 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> delta_;
131 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> gamma_;
132 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> alpha_;
133 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> beta_x_;
134 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> beta_y_;
135 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> tmp_ones_;
136 typename Eigen::Array<Scalar, 3, 4> position_;
137
138 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> rb_accx_max_;
139 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> rb_accy_max_;
140 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic>
141 rb_accx_max_bool_;
142 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic>
143 rb_accy_max_bool_;
144
145 // Cost on the velocity of the feet :
146 bool is_vel_activated_; // Boolean to activate the cost on the velocity of
147 // the feet
148 Scalar vel_weight_; // Weight on the velocity cost
149 typename Eigen::Matrix<Scalar, 2, 1>
150 vel_lim_; // Maximum velocity allowed on x and y axis
151 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> gamma_v;
152 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> alpha_v;
153 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> beta_x_v;
154 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> beta_y_v;
155
156 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> rb_velx_max_;
157 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> rb_vely_max_;
158 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic>
159 rb_velx_max_bool_;
160 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic>
161 rb_vely_max_bool_;
162
163 // Cost on the jerk of the feet
164 bool is_jerk_activated_;
165 Scalar jerk_weight_;
166 Scalar alpha_j;
167 typename Eigen::Array<Scalar, Eigen::Dynamic, Eigen::Dynamic> beta_j;
168 typename Eigen::Array<Scalar, 3, 4> jerk_;
169
170 typename Eigen::Matrix<Scalar, 2, 4> rb_jerk_;
171
172 typename Eigen::Matrix<Scalar, 3, 3> oRh_;
173 typename Eigen::Matrix<Scalar, 3, 1> oTh_;
174 };
175
176 template <typename _Scalar>
177 struct ActionDataQuadrupedStepTpl
178 : public crocoddyl::ActionDataAbstractTpl<_Scalar> {
179 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
180
181 typedef _Scalar Scalar;
182 typedef crocoddyl::MathBaseTpl<Scalar> MathBase;
183 typedef crocoddyl::ActionDataAbstractTpl<Scalar> Base;
184 using Base::cost;
185 using Base::Fu;
186 using Base::Fx;
187 using Base::Lu;
188 using Base::Luu;
189 using Base::Lx;
190 using Base::Lxu;
191 using Base::Lxx;
192 using Base::r;
193 using Base::xnext;
194
195 template <template <typename Scalar> class Model>
196 explicit ActionDataQuadrupedStepTpl(Model<Scalar>* const model)
197 : crocoddyl::ActionDataAbstractTpl<Scalar>(model) {}
198 };
199
200 /* --- Details -------------------------------------------------------------- */
201 /* --- Details -------------------------------------------------------------- */
202 /* --- Details -------------------------------------------------------------- */
203
204 typedef ActionModelQuadrupedStepTpl<double> ActionModelQuadrupedStep;
205 typedef ActionDataQuadrupedStepTpl<double> ActionDataQuadrupedStep;
206
207 } // namespace quadruped_walkgen
208
209 #include "quadruped_step.hxx"
210
211 #endif
212