TurtleQUAD 2.0
Loading...
Searching...
No Matches
Leg Class Reference

Quadruped Leg. More...

#include <Leg.hpp>

Public Types

enum  state_t {
  IDLE , HOMING , RUNNING , LIFT ,
  PLACE
}
 Leg State.

Public Member Functions

 Leg (Eigen::Vector< double, njoints+1 > &l, Eigen::Matrix< double, 6, njoints > &Slist, Eigen::Isometry3d &M, std::array< Eigen::Isometry3d, njoints+1 > &Mlist, std::array< Eigen::Matrix6d, njoints > &Glist, Eigen::Matrix< double, njoints, 2 > &thetaRange, Eigen::Vector< double, njoints > &thetadMax, Eigen::Vector< double, njoints > &thetaddMax, Eigen::Vector< double, njoints > &tauMax)
 Leg Constructor.
bool fk (const Eigen::Vector3d &thetalist, Eigen::Vector3d &pf)
 Forward Kinematics.
bool ik (const Eigen::Vector3d &pf, Eigen::Vector3d &thetalist, Eigen::Matrix3d *Jinv=nullptr)
 Inverse Kinematics.
bool ivk (const Eigen::Vector3d &vf, const Eigen::Matrix3d &Jinv, Eigen::Vector3d &thetadlist)
 Inverse Velocity Kinematics.
bool id (Eigen::Vector< double, njoints > &taulist)
 Inverse Dynamics.
void liftTo (const Eigen::Isometry3d &T)
bool jointTrajectory (const Eigen::Isometry3d &Tstart, const Eigen::Isometry3d &Tgoal, const double t0, const double t, Eigen::Isometry3d &Tcurrent)
 Joint Trajectory.
void run ()
 Run foot operations.

Public Attributes

enum Leg::state_t state = IDLE
enum Leg::state_t statep = IDLE
Eigen::Vector3d pf
 Foot position [m].
Eigen::Vector3d vf
 Foot velocity [m/s].
Eigen::Vector3d dvf
 Foot acceleration [m/s^2].
Eigen::Vector3d ff
 Foot force [N].
Eigen::Vector3d g
 Gravity [m/s^2].
Eigen::Vector< double, njoints > thetalist
Eigen::Vector< double, njoints > thetadlist
Eigen::Vector< double, njoints > thetaddlist
Eigen::Vector< double, njoints > taulist

Private Attributes

const Eigen::Vector< double, njoints+1 > l
const Eigen::Matrix< double, 6, njoints > Slist
const Eigen::Isometry3d M
const std::array< Eigen::Isometry3d, njoints+1 > Mlist
const std::array< Eigen::Matrix6d, njoints > Glist
const Eigen::Matrix< double, njoints, 2 > thetaRange
const Eigen::Vector< double, njoints > thetadMax
const Eigen::Vector< double, njoints > thetaddMax
const Eigen::Vector< double, njoints > tauMax
const Eigen::Vector< double, njoints > thetadir
Eigen::Matrix< double, njoints, 3 > Jinv
Eigen::Isometry3d Mi
Eigen::Matrix< double, 6, njoints > Ai
Eigen::Matrix< double, 6, njoints+1 > Vi
Eigen::Matrix< double, 6, njoints+1 > dVi
std::array< Eigen::Matrix6d, njoints+1 > AdTi
Eigen::Vector6d Fi

Detailed Description

Quadruped Leg.

The leg class contains gemotry and mass properties for one leg, the leg state, and functions to operate on the leg state.

Constructor & Destructor Documentation

◆ Leg()

Leg::Leg ( Eigen::Vector< double, njoints+1 > & l,
Eigen::Matrix< double, 6, njoints > & Slist,
Eigen::Isometry3d & M,
std::array< Eigen::Isometry3d, njoints+1 > & Mlist,
std::array< Eigen::Matrix6d, njoints > & Glist,
Eigen::Matrix< double, njoints, 2 > & thetaRange,
Eigen::Vector< double, njoints > & thetadMax,
Eigen::Vector< double, njoints > & thetaddMax,
Eigen::Vector< double, njoints > & tauMax )
inline

Leg Constructor.

Parameters
[in]l4-vector of leg lengths
[in]Slist6x3 list of joint screw axes
[in]MTransform of the leg at zero joint angles
[in]MlistArray of 4 transforms between joints at zero joint angles, beginning from the base (Identity)
[in]GlistArray of 3 6x6 spatial inertia matrices for the leg links
[in]thetaRange3x2 matrix of joint angle limits [low, high]
[in]thetadMax3-vector of joint velocity limits
[in]thetaddMax3-vector of joint acceleration limits
[in]tauMax3-vector of joint torque limits

Member Function Documentation

◆ fk()

bool Leg::fk ( const Eigen::Vector3d & thetalist,
Eigen::Vector3d & pf )

Forward Kinematics.

Compute foot position from joint angles

Parameters
[in]thetalist3-vector of joint angles
[out]pf3-vector resultant foot position

◆ id()

bool Leg::id ( Eigen::Vector< double, njoints > & taulist)

Inverse Dynamics.

Compute joint torque from foot state

Parameters
[out]taulistjoint torques

◆ ik()

bool Leg::ik ( const Eigen::Vector3d & pf,
Eigen::Vector3d & thetalist,
Eigen::Matrix3d * Jinv = nullptr )

Inverse Kinematics.

Compute joint angles (and Jacobian inverse) at a given foot position

Parameters
[in]pf3-vector foot position
[out]thetalist3-vector resultant joint angles
[out]Jinv3x3 resultant Jacobian inverse (dtheta/dp)

◆ ivk()

bool Leg::ivk ( const Eigen::Vector3d & vf,
const Eigen::Matrix3d & Jinv,
Eigen::Vector3d & thetadlist )

Inverse Velocity Kinematics.

Compute joint velocities for a given foot position velocity

Parameters
[in]vf3-vector foot velocity
[in]Jinv3x3 Jacobian inverse at the current position (thetad/dp)
[out]thetadlist3-vector resultant joint angles

◆ jointTrajectory()

bool Leg::jointTrajectory ( const Eigen::Isometry3d & Tstart,
const Eigen::Isometry3d & Tgoal,
const double t0,
const double t,
Eigen::Isometry3d & Tcurrent )

Joint Trajectory.

Compute joint angles at a specified time on a joint trajectory

Parameters
[in]TstartSE(3) beginning foot pose
[in]TgoalSE(3) ending foot pose
[in]t0Time at beginning of trajectory
[in]tCurrent time
[out]TSE(3) current foot pose

Member Data Documentation

◆ thetadir

const Eigen::Vector<double, njoints> Leg::thetadir
private
Initial value:
{Slist(0, 0) * Slist(1, 1),
Slist(1, 1), Slist(1, 1)}

The documentation for this class was generated from the following files: