Skip to content
Snippets Groups Projects
Commit 91edb354 authored by odri's avatar odri
Browse files

Add new gaits

parent e2ac5143
No related branches found
No related tags found
No related merge requests found
......@@ -120,6 +120,14 @@ class Gait {
////////////////////////////////////////////////////////////////////////////////////////////////
void create_trot();
////////////////////////////////////////////////////////////////////////////////////////////////
///
/// \brief Create a trot gait with diagonaly opposed legs moving at the same time and some
/// 4-stance phases
///
////////////////////////////////////////////////////////////////////////////////////////////////
void create_walking_trot();
////////////////////////////////////////////////////////////////////////////////////////////////
///
/// \brief Create a pacing gait with legs on the same side (left or right) moving at the same time
......@@ -141,6 +149,20 @@ class Gait {
////////////////////////////////////////////////////////////////////////////////////////////////
void create_static();
////////////////////////////////////////////////////////////////////////////////////////////////
///
/// \brief Create a transverse gallop gait
///
////////////////////////////////////////////////////////////////////////////////////////////////
void create_transverse_gallop();
////////////////////////////////////////////////////////////////////////////////////////////////
///
/// \brief Create a custom gallop gait
///
////////////////////////////////////////////////////////////////////////////////////////////////
void create_custom_gallop();
////////////////////////////////////////////////////////////////////////////////////////////////
///
/// \brief Initialize content of the gait matrix based on the desired gait, the gait period and
......
......@@ -40,13 +40,13 @@ void Gait::create_walk() {
desiredGait_ = MatrixN::Zero(currentGait_.rows(), 4);
Eigen::Matrix<double, 1, 4> sequence;
sequence << 0.0, 1.0, 1.0, 1.0;
sequence << 1.0, 0.0, 1.0, 0.0;
desiredGait_.block(0, 0, N, 4) = sequence.colwise().replicate(N);
sequence << 1.0, 0.0, 1.0, 1.0;
sequence << 1.0, 0.0, 0.0, 1.0;
desiredGait_.block(N, 0, N, 4) = sequence.colwise().replicate(N);
sequence << 1.0, 1.0, 0.0, 1.0;
sequence << 0.0, 1.0, 0.0, 1.0;
desiredGait_.block(2 * N, 0, N, 4) = sequence.colwise().replicate(N);
sequence << 1.0, 1.0, 1.0, 0.0;
sequence << 0.0, 1.0, 1.0, 0.0;
desiredGait_.block(3 * N, 0, N, 4) = sequence.colwise().replicate(N);
}
......@@ -63,6 +63,24 @@ void Gait::create_trot() {
desiredGait_.block(N, 0, N, 4) = sequence.colwise().replicate(N);
}
void Gait::create_walking_trot() {
// Number of timesteps in a half period of gait
int N = (int)std::lround(0.5 * T_gait_ / dt_);
desiredGait_ = MatrixN::Zero(currentGait_.rows(), 4);
int M = 8;
Eigen::Matrix<double, 1, 4> sequence;
sequence << 1.0, 0.0, 0.0, 1.0;
desiredGait_.block(0, 0, N-M, 4) = sequence.colwise().replicate(N);
sequence << 1.0, 1.0, 1.0, 1.0;
desiredGait_.block(N-M, 0, M, 4) = sequence.colwise().replicate(N);
sequence << 0.0, 1.0, 1.0, 0.0;
desiredGait_.block(N, 0, N-M, 4) = sequence.colwise().replicate(N);
sequence << 1.0, 1.0, 1.0, 1.0;
desiredGait_.block(2*N-M, 0, M, 4) = sequence.colwise().replicate(N);
}
void Gait::create_pacing() {
// Number of timesteps in a half period of gait
int N = (int)std::lround(0.5 * T_gait_ / dt_);
......@@ -100,6 +118,41 @@ void Gait::create_static() {
desiredGait_.block(0, 0, N, 4) = sequence.colwise().replicate(N);
}
void Gait::create_transverse_gallop() {
// Number of timesteps in a half period of gait
int N = (int)std::lround(0.25 * T_gait_ / dt_);
desiredGait_ = MatrixN::Zero(currentGait_.rows(), 4);
Eigen::Matrix<double, 1, 4> sequence;
sequence << 0.0, 0.0, 1.0, 0.0;
desiredGait_.block(0, 0, N, 4) = sequence.colwise().replicate(N);
sequence << 1.0, 0.0, 0.0, 0.0;
desiredGait_.block(N, 0, N, 4) = sequence.colwise().replicate(N);
sequence << 0.0, 0.0, 0.0, 1.0;
desiredGait_.block(2*N, 0, N, 4) = sequence.colwise().replicate(N);
sequence << 0.0, 1.0, 0.0, 0.0;
desiredGait_.block(3*N, 0, N, 4) = sequence.colwise().replicate(N);
}
void Gait::create_custom_gallop() {
// Number of timesteps in a half period of gait
int N = (int)std::lround(0.25 * T_gait_ / dt_);
desiredGait_ = MatrixN::Zero(currentGait_.rows(), 4);
Eigen::Matrix<double, 1, 4> sequence;
sequence << 1.0, 0.0, 1.0, 0.0;
desiredGait_.block(0, 0, N, 4) = sequence.colwise().replicate(N);
sequence << 1.0, 0.0, 0.0, 1.0;
desiredGait_.block(N, 0, N, 4) = sequence.colwise().replicate(N);
sequence << 0.0, 1.0, 0.0, 1.0;
desiredGait_.block(2*N, 0, N, 4) = sequence.colwise().replicate(N);
sequence << 0.0, 1.0, 1.0, 0.0;
desiredGait_.block(3*N, 0, N, 4) = sequence.colwise().replicate(N);
}
void Gait::create_gait_f() {
int i = 0;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment