Skip to content

Commit 81f3311

Browse files
author
Alexander Winkler
committed
ee_motion_phases now parametrized with p_start and p_end each
1 parent 14c8c06 commit 81f3311

12 files changed

+184
-92
lines changed

CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,7 @@ add_library(${MOTION_OPT_LIB}
9292
src/motion_factory.cc
9393
src/linear_spline_equations.cc
9494
# endeffector
95-
src/ee_swing_motion.cc
95+
src/ee_phase_motion.cc
9696
src/ee_motion.cc
9797
src/endeffectors_motion.cc
9898
src/endeffector_load.cc
@@ -174,7 +174,7 @@ if(BUILD_TESTS)
174174
# test/google/ipopt_test.cc
175175
# # general
176176
# test/google/sparse_matrix_test.cc
177-
test/google/ee_swing_motion_test.cc
177+
test/google/ee_phase_motion_test.cc
178178
test/google/ee_motion_test.cc
179179
## these should be kept well maintained
180180
test/dynamic_constraint_test.cc

config/ipopt.opt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ tol 0.01 # usually 0.01
2929

3030

3131
#bound_relax_factor 0.01
32-
max_cpu_time 5.1
32+
max_cpu_time 15.1
3333
#max_iter 2
3434
#bound_frac 0.5
3535

include/xpp/opt/ee_motion.h

Lines changed: 14 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -8,12 +8,12 @@
88
#ifndef XPP_XPP_OPT_INCLUDE_XPP_OPT_EE_MOTION_H_
99
#define XPP_XPP_OPT_INCLUDE_XPP_OPT_EE_MOTION_H_
1010

11-
#include <xpp/opt/ee_swing_motion.h>
1211
#include <xpp/contact.h>
1312
#include <xpp/parametrization.h>
1413

1514
#include <Eigen/Sparse>
1615
#include <deque>
16+
#include "ee_phase_motion.h"
1717

1818
namespace xpp {
1919
namespace opt {
@@ -23,12 +23,11 @@ namespace opt {
2323
class EEMotion : public Parametrization {
2424
public:
2525
using ContactPositions = std::deque<Contact>;
26-
using JacobianRow = Eigen::SparseVector<double, Eigen::RowMajor>;
26+
using PhaseContacts = std::array<Contact, 2>;
2727

2828
EEMotion ();
2929
virtual ~EEMotion ();
3030

31-
3231
void SetInitialPos(const Vector3d& pos, EndeffectorID);
3332
void AddStancePhase(double t);
3433
void AddSwingPhase(double t, const Vector3d& goal);
@@ -44,22 +43,29 @@ class EEMotion : public Parametrization {
4443
ContactPositions GetContact(double t_global) const;
4544

4645

47-
4846
VectorXd GetOptimizationParameters() const override;
4947
void SetOptimizationParameters(const VectorXd&) override;
5048
// haven't yet implemented the derivative during swing phase
51-
// JacobianRow GetJacobianPos(double t, d2::Coords dimension) const;
49+
JacobianRow GetJacobianPos(double t, d2::Coords dimension) const;
5250
int Index(int id, d2::Coords dimension) const;
5351

5452

5553
private:
5654
int GetPhase(double t_global) const;
57-
void AddPhase(double t, const Vector3d& goal, double lift_height);
55+
void AddPhase(double t, const Vector3d& goal, double lift_height, int id_goal);
5856
void UpdateSwingMotions();
57+
double GetLocalTime(double t_global, int phase) const;
58+
59+
Contact GetLastContact() const;
60+
61+
// ContactPositions contacts_;
62+
Contact first_contact_;
63+
int n_steps = 0;
64+
65+
std::vector<PhaseContacts> phase_contacts_;
5966

60-
ContactPositions contacts_;
6167
std::deque<bool> is_contact_phase_; // zmp_ this deserves a separate class
62-
std::vector<EESwingMotion> phase_motion_;
68+
std::vector<EEPhaseMotion> phase_motion_;
6369

6470
};
6571

include/xpp/opt/ee_swing_motion.h renamed to include/xpp/opt/ee_phase_motion.h

Lines changed: 11 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
/**
2-
@file ee_swing_motion.h
2+
@file ee_phase_motion.h
33
@author Alexander W. Winkler ([email protected])
44
@date Jan 16, 2017
55
@brief Brief description
@@ -17,16 +17,16 @@ namespace opt {
1717

1818
/** Parametrizes the motion from one 3D point to another.
1919
*
20-
* This can be used to generate the swingleg motion given two footholds.
21-
* See xpp_opt/matlab/swingleg_z_height.m for the generation of these values.
20+
* This can be used to generate the swingleg motion given two footholds or
21+
* represent a leg in stance ("movement" between the same start/goal).
2222
*/
23-
class EESwingMotion {
23+
class EEPhaseMotion {
2424
public:
25-
using PolyXY = PolynomialXd<CubicPolynomial, StateLin2d>;
26-
using PolyZ = LiftHeightPolynomial;
25+
using PolyXY = PolynomialXd<CubicPolynomial, StateLin2d>;
26+
using PolyZ = LiftHeightPolynomial;
2727

28-
EESwingMotion ();
29-
virtual ~EESwingMotion ();
28+
EEPhaseMotion ();
29+
virtual ~EEPhaseMotion ();
3030

3131
/** Completely parametrizes the motion.
3232
*
@@ -52,6 +52,9 @@ class EESwingMotion {
5252
StateLin3d GetState(double t_local) const;
5353
double GetDuration() const;
5454

55+
double GetDerivativeOfPosWrtContactsXY(d2::Coords dim, double t_local,
56+
Polynomial::PointType p) const;
57+
5558
private:
5659
PolyZ poly_z_;
5760
PolyXY poly_xy_;

include/xpp/opt/impl/polynomial_xd-impl.h

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,12 @@ bool PolynomialXd<PolynomialType, PointType>::GetPoint(const double dt,
7878
return true;
7979
}
8080

81+
template<typename PolynomialType, typename PointType>
82+
PolynomialType
83+
PolynomialXd<PolynomialType, PointType>::GetDim (int dim) const
84+
{
85+
return polynomials_.at(dim);
86+
}
8187

8288
} // namespace opt
8389
} // namespace xpp

include/xpp/opt/polynomial.h

Lines changed: 12 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -25,9 +25,9 @@ namespace opt {
2525
/** Constructs a polynomial given start and end states.
2626
*
2727
* The polynomial types are:
28-
* Linear: Ex + F;
29-
* Cubic: Dx^2 + Ex + F;
30-
* Quintic: At^5 + Bt^4 + Ct^3 + Dt^2 + Et + f
28+
* Linear: Et + F;
29+
* Cubic: Ct^3 + Dt^2 + Et + F;
30+
* Quintic: At^5 + Bt^4 + Ct^3 + Dt^2 + Et + F
3131
*/
3232
class Polynomial {
3333
public:
@@ -36,6 +36,8 @@ class Polynomial {
3636
enum PolynomialCoeff { A=0, B, C, D, E, F };
3737
static constexpr std::array<PolynomialCoeff, 6> AllSplineCoeff = {{A,B,C,D,E,F}};
3838

39+
enum PointType {Start=0, Goal=1};
40+
3941
public:
4042
Polynomial();
4143
virtual ~Polynomial() {};
@@ -61,10 +63,10 @@ class Polynomial {
6163
double GetDuration() const;
6264

6365
protected:
66+
double duration;
6467
std::array< double, AllSplineCoeff.size() > c; //!< coefficients of spline
6568

6669
private:
67-
double duration;
6870
/**
6971
* @brief Calculates all spline coeff of current spline.
7072
*
@@ -105,13 +107,19 @@ class LinearPolynomial : public Polynomial {
105107
void SetPolynomialCoefficients(double T, const StateLin1d& start, const StateLin1d& end);
106108
};
107109

110+
/** @brief a polynomial of the form ct^3 + dt^2 + et + f.
111+
* see matlab script "third_order_poly.m" for generation of these values.
112+
*/
108113
class CubicPolynomial : public Polynomial {
109114
public:
110115
CubicPolynomial() {};
111116
~CubicPolynomial() {};
112117

113118
static int GetNumCoeff() { return 4; }; //C,D,E,F
114119

120+
// spring_clean_ move up to base class?
121+
double GetDerivativeOfPosWrtPos(double t, PointType p) const;
122+
115123
private:
116124
void SetPolynomialCoefficients(double T, const StateLin1d& start, const StateLin1d& end);
117125
};

include/xpp/opt/polynomial_xd.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,13 +36,17 @@ class PolynomialXd {
3636
double GetCoefficient(int dim, PolyCoeff coeff) const;
3737
void SetCoefficients(int dim, PolyCoeff coeff, double value);
3838

39+
3940
static int GetNumCoeff() { return PolynomialType::GetNumCoeff(); };
4041

4142
double GetDuration() const;
4243

4344
uint GetId() const { return id_; };
4445
void SetId(uint id) { id_ = id; };
4546

47+
PolynomialType GetDim(int dim) const;
48+
49+
4650
private:
4751
std::array<PolynomialType, kNumDim> polynomials_; ///< X,Y,Z dimensions
4852
uint id_; // to identify the order relative to other polynomials

matlab/third_order_poly.m

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -2,21 +2,21 @@
22
clear all;
33

44
% 3rd order poly
5-
syms a b c d t p1 p2 t1 t2
5+
syms a b c d t p0 p1 v0 v1 T
66
p = a*t^3 + b*t^2 + c*t + d;
77
pv = diff(p, t);
88

99

1010
% initial position and velocity are zero
1111
t = 0;
12-
eq_init_p = subs(p) == p1
13-
eq_init_v = subs(pv) == 0
12+
eq_init_p = subs(p) == p0
13+
eq_init_v = subs(pv) == v0
1414

1515

1616
% final position and velocity are zero (at time t=1)
17-
t = t2;
18-
eq_final_p = subs(p) == p2
19-
eq_final_v = subs(pv) == 0
17+
t = T;
18+
eq_final_p = subs(p) == p1
19+
eq_final_v = subs(pv) == v1
2020

2121

2222
% solve the system of equations for the polynomial coefficients
@@ -28,4 +28,8 @@
2828
d = S.d
2929

3030
syms t;
31-
pretty(subs(p))
31+
pretty(subs(p))
32+
33+
34+
% Get the derivative w.r.t the initial and final position
35+
jac_p = jacobian(subs(p), [p0 p1])

0 commit comments

Comments
 (0)