File: State.hpp

package info (click to toggle)
dart 6.12.1%2Bdfsg4-12
  • links: PTS, VCS
  • area: main
  • in suites: bookworm
  • size: 57,000 kB
  • sloc: cpp: 269,461; python: 3,911; xml: 1,273; sh: 404; makefile: 30
file content (335 lines) | stat: -rw-r--r-- 10,781 bytes parent folder | download | duplicates (2)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
/*
 * Copyright (c) 2011-2021, The DART development contributors
 * All rights reserved.
 *
 * The list of contributors can be found at:
 *   https://github.com/dartsim/dart/blob/master/LICENSE
 *
 * This file is provided under the following "BSD-style" License:
 *   Redistribution and use in source and binary forms, with or
 *   without modification, are permitted provided that the following
 *   conditions are met:
 *   * Redistributions of source code must retain the above copyright
 *     notice, this list of conditions and the following disclaimer.
 *   * Redistributions in binary form must reproduce the above
 *     copyright notice, this list of conditions and the following
 *     disclaimer in the documentation and/or other materials provided
 *     with the distribution.
 *   THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
 *   CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
 *   INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
 *   MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
 *   DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
 *   CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
 *   SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
 *   LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
 *   USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
 *   AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 *   LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 *   ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 *   POSSIBILITY OF SUCH DAMAGE.
 */

#ifndef EXAMPLES_ATLASSIMBICON_STATE_HPP_
#define EXAMPLES_ATLASSIMBICON_STATE_HPP_

#include <map>
#include <string>
#include <vector>

#include <Eigen/Dense>
#include <dart/dart.hpp>

#define ATLAS_DEFAULT_KD 1.0 // No more than 1.0
#define ATLAS_DEFAULT_KP 1e+3

#define ATLAS_DEFAULT_SAGITAL_CD 0.1
#define ATLAS_DEFAULT_SAGITAL_CV 0.1

#define ATLAS_DEFAULT_CORONAL_CD 0.1
#define ATLAS_DEFAULT_CORONAL_CV 0.1

namespace dart {
namespace dynamics {
class BodyNode;
class Joint;
class Skeleton;
} // namespace dynamics
} // namespace dart

class TerminalCondition;

//==============================================================================
/// \brief class State
class State
{
public:
  /// \brief Constructor
  explicit State(
      dart::dynamics::SkeletonPtr _skeleton, const std::string& _name);

  /// \brief Destructor
  virtual ~State();

  //------------------------------- Setting ------------------------------------
  /// \brief Set name
  void setName(std::string& _name);

  /// \brief Get name
  const std::string& getName() const;

  /// \brief Set next state
  void setNextState(State* _nextState);

  /// \brief Add terminal condition
  void setTerminalCondition(TerminalCondition* _condition);

  /// \brief Get next state
  State* getNextState() const;

  /// \brief Get elapsed time
  double getElapsedTime() const;

  //----------------------- Setting Desired Position ---------------------------
  /// \brief Set desired joint position whose name is _jointName
  void setDesiredJointPosition(const std::string& _jointName, double _val);

  /// \brief Get desired joint position whose index is _idx
  double getDesiredJointPosition(int _idx) const;

  /// \brief Get desired joint position whose name is _jointName
  double getDesiredJointPosition(const std::string& _jointName) const;

  /// \brief Set desired global angle swing leg on sagital plane
  void setDesiredSwingLegGlobalAngleOnSagital(double _val);

  /// \brief Set desired global angle swing leg on coronal plane
  void setDesiredSwingLegGlobalAngleOnCoronal(double _val);

  /// \brief Set desired global angle pelvis on sagital plane
  void setDesiredPelvisGlobalAngleOnSagital(double _val);

  /// \brief Set desired global angle of pelvis on coronal plane
  void setDesiredPelvisGlobalAngleOnCoronal(double _val);

  /// \brief Set proportional gain for PD controller
  void setProportionalGain(int _idx, double _val);

  /// \brief Set proportional gain for PD controller
  void setProportionalGain(const std::string& _jointName, double _val);

  /// \brief Get proportional gain for PD controller
  double getProportionalGain(int _idx) const;

  /// \brief Get proportional gain for PD controller
  double getProportionalGain(const std::string& _jointName) const;

  /// \brief Set derivative gain for PD controller
  void setDerivativeGain(int _idx, double _val);

  /// \brief Set derivative gain for PD controller
  void setDerivativeGain(const std::string& _jointName, double _val);

  /// \brief Get derivative gain for PD controller
  double getDerivativeGain(int _idx) const;

  // /// \brief Get derivative gain for PD controller
  // double getDerivativeGain(const std::string& _jointName) const;

  /// \brief Set balance feedback gain parameter for sagital com distance
  void setFeedbackSagitalCOMDistance(std::size_t _index, double _val);

  /// \brief Set balance feedback gain parameter for sagital com velocity
  void setFeedbackSagitalCOMVelocity(std::size_t _index, double _val);

  /// \brief Set balance feedback gain parameter for sagital com distance
  void setFeedbackCoronalCOMDistance(std::size_t _index, double _val);

  /// \brief Set balance feedback gain parameter for sagital com velocity
  void setFeedbackCoronalCOMVelocity(std::size_t _index, double _val);

  /// \brief Set stance foot to left foot
  void setStanceFootToLeftFoot();

  /// \brief Set stance foot to right foot
  void setStanceFootToRightFoot();

  //------------------------------- Control ------------------------------------
  /// \brief Initiate state. This is called when the state machine transite
  ///        from the previous state to this state.
  virtual void begin(double _currentTime);

  /// \brief Compute control force and apply it to Atlas robot
  virtual void computeControlForce(double _timestep);

  /// \brief Check if terminal condision is satisfied
  virtual bool isTerminalConditionSatisfied() const;

  /// \brief Finalize state. This is called when the state machine stransite
  ///        from this state to the next state.
  virtual void end(double _currentTime);

protected:
  /// \brief Get center of mass
  Eigen::Vector3d getCOM() const;

  /// \brief Get velocity of center of mass
  Eigen::Vector3d getCOMVelocity() const;

  /// \brief Get a frame such that:
  ///        1) The origin is at the COM
  ///        2) The z-axis is perpendicular to the ground (y-axis by default)
  ///        3) The x-axis is a projected x-axis of pelvis on to perpendicular
  ///           plane against to the z-axis
  Eigen::Isometry3d getCOMFrame() const;

  /// \brief Get sagital com distance
  double getSagitalCOMDistance();

  /// \brief Get sagital com velocity
  double getSagitalCOMVelocity();

  /// \brief Get coronal com distance
  double getCoronalCOMDistance();

  /// \brief Get coronal com velocity
  double getCoronalCOMVelocity();

  /// \brief Get stance ankle position
  Eigen::Vector3d getStanceAnklePosition() const;

  /// \brief Get left ankle position
  Eigen::Vector3d getLeftAnklePosition() const;

  /// \brief Get right ankle position
  Eigen::Vector3d getRightAnklePosition() const;

  // TODO(JS): Not implemented yet
  /// \brief Get global pelvis upvector angle on sagital plane
  double getSagitalPelvisAngle() const;

  // TODO(JS): Not implemented yet
  /// \brief Get global pelvis upvector angle on coronal plane
  double getCoronalPelvisAngle() const;

  /// \brief Get global left leg angle on sagital plane
  double getSagitalLeftLegAngle() const;

  /// \brief Get global right leg angle on sagital plane
  double getSagitalRightLegAngle() const;

  /// \brief Get global left leg angle on coronal plane
  double getCoronalLeftLegAngle() const;

  /// \brief Get global right leg angle on coronal plane
  double getCoronalRightLegAngle() const;

  /// \brief Name
  std::string mName;

  /// \brief Target skeleton for control
  dart::dynamics::SkeletonPtr mSkeleton;

  /// \brief Next state. Default is myself.
  State* mNextState;

  /// \brief Terminal condition
  TerminalCondition* mTerminalCondition;

  /// \brief Started time
  double mBeginTime;

  /// \brief Stopped time
  double mEndTime;

  /// \brief Frame number
  int mFrame;

  /// \brief Elapsed time which is stopped time minus started time
  double mElapsedTime;

  /// \brief Desired joint positions
  Eigen::VectorXd mDesiredJointPositions;

  /// \brief Desired global angle of swing leg on sagital plane
  double mDesiredGlobalSwingLegAngleOnSagital;

  /// \brief Desired global angle of swing leg on coronal plane
  double mDesiredGlobalSwingLegAngleOnCoronal;

  /// \brief Desired global angle of pelvis on sagital plane
  double mDesiredGlobalPelvisAngleOnSagital;

  /// \brief Desired global angle of pelvis on coronal plane
  double mDesiredGlobalPelvisAngleOnCoronal;

  /// \brief Proportional gain for PD controller
  Eigen::VectorXd mKp;

  /// \brief Derivative gain PD controller
  Eigen::VectorXd mKd;

  /// \brief Feedback gain for com
  Eigen::VectorXd mSagitalCd;

  /// \brief Feedback gain for velocity of com
  Eigen::VectorXd mSagitalCv;

  /// \brief Feedback gain for com
  Eigen::VectorXd mCoronalCd;

  /// \brief Feedback gain for velocity of com
  Eigen::VectorXd mCoronalCv;

  /// \brief Computeed control force
  Eigen::VectorXd mTorque;

  /// \brief Joint map
  std::map<const std::string, int> mJointMap;

private:
  /// \brief Get the parent joint's position of _bodyNode
  Eigen::Vector3d _getJointPosition(dart::dynamics::BodyNode* _bodyNode) const;

  /// \brief Compute the angle between two vectors
  double _getAngleBetweenTwoVectors(
      const Eigen::Vector3d& _v1, const Eigen::Vector3d& _v2) const;

  /// \brief Update torque for torso and swing hip
  void _updateTorqueForStanceLeg();

  /// \brief Pelvis body node
  dart::dynamics::BodyNode* mPelvis;

  /// \brief Left foot body node
  dart::dynamics::BodyNode* mLeftThigh;

  /// \brief Right foot body node
  dart::dynamics::BodyNode* mRightThigh;

  /// \brief Left foot body node
  dart::dynamics::BodyNode* mStanceFoot;

  /// \brief Left foot body node
  dart::dynamics::BodyNode* mLeftFoot;

  /// \brief Right foot body node
  dart::dynamics::BodyNode* mRightFoot;

  /// \brief Index for coronal left hip
  std::size_t mCoronalLeftHip;

  /// \brief Index for coronal right hip
  std::size_t mCoronalRightHip;

  /// \brief Index for sagital left hip
  std::size_t mSagitalLeftHip;

  /// \brief Index for sagital right hip
  std::size_t mSagitalRightHip;

  /// \brief Desired joint positions with balance feedback
  Eigen::VectorXd mDesiredJointPositionsBalance;
};

#endif // EXAMPLES_ATLASSIMBICON_STATE_HPP_