Koduino
Public Member Functions | Static Public Attributes | List of all members
MinitaurLeg Class Reference

Class for coordinating two parallel coaxial motors in the Minitaur config. More...

#include <MinitaurLeg.h>

Detailed Description

Class for coordinating two parallel coaxial motors in the Minitaur config.

Link lengths can be set, and kinematics are implemented. The user can choose to use meters for the extension, or a nonlinear mapping from 0 (folded up) to pi (all the way extended)

This class is derived from AbstractMotor, in particular it coordinates two motors together in a parallel five-bar configuration.

Kinematics

The kinematics of the leg can be found in http://kodlab.seas.upenn.edu/Gavin/IROS15. In particular, Fig. 1 (borrowed from the paper and included below) will be helpful to follow this help page.

Minitaur leg kinematics definitions

The end-effector coordinates (first argument to MinitaurLeg::setOpenLoop(), MinitaurLeg::setGain(), and MinitaurLeg::setPosition()) are EXTENSION and ANGLE. Assuming the inidividual motor zeros are set when the upper links are pointing vertically up, and the motor directions are set so the positions increase as the motors sweep down (this is the default of Minitaur),

Usage

To use a MinitaurLeg in your code, follow the usage steps in the AbstractMotor help page. Additionally,

  1. Set MinitaurLeg::useLengths to true if you would like to use the r coordinate instead of β for the leg extension
  2. Set the upper link length MinitaurLeg::l1 (default is 0.1 m) and the lower link length MinitaurLeg::l2 (default is 0.2 m)
  3. You can call MinitaurLeg::getSpeed() to get a body speed estimate if you supply the body pitch (leaning forward is assumed to be positive pitch).
  4. To get proprioceptive torque estimates, you can still use Motor::getTorque() as long as Motor::setTorqueEstParams() has been called.

Example

#include <Motor.h>
#include <MinitaurLeg.h>
// Uncomment the lines corresponding to your board
// MBLC 0.5
const int NMOT = 10;
const uint8_t outPin[] = {PE9, PE11, PE13, PE14, PA0, PD4, PD7, PD6, PB4, PB5};
const uint8_t inPin[] = {PD12, PD13, PD14, PD15, PC6, PC7, PC8, PC9, PE2, PE3};
// // Mainboard v1.1
// const int NMOT = 8;
// const uint8_t outPin[] = {PA0, PA11, PA2, PA3, PB0, PB8, PA14, PA1};
// const uint8_t inPin[] = {PA6, PB5, PB6, PB7, PB1, PB9, PA15, PA5};
// // Mainboard v2
// const int NMOT = 8;
// const uint8_t outPin[] = {PA3, PA2, PA0, PA1, PB0, PB1, PA6, PB5};
// const uint8_t inPin[] = {PB8, PB9, PB3, PA8, PA11, PA15, PB14, PB15};
const int CONTROL_RATE = 1000;
BlCon34 M[NMOT];
MinitaurLeg leg0(&M[1], &M[0]);
const float motZeros[NMOT] = {0,0,0,0,0,0,0,0,0,0};
void controlLoop() {
leg0.update();
}
void setup() {
Serial1.begin(115200);
Motor::updateRate = CONTROL_RATE;
// Arguments are pwmPin, pulsePin, zero(rad), direction(+/- 1)
for (int i=0; i<NMOT; ++i)
M[i].init(outPin[i], inPin[i], motZeros[i], 1);
attachTimerInterrupt(0, controlLoop, CONTROL_RATE);
}
void loop() {
leg0.enable(true);
// These commands are similar to Motor commands, except with an added first argument
leg0.setGain(ANGLE, 0.3);
leg0.setPosition(ANGLE, 0);
leg0.setOpenLoop(EXTENSION, 0.1);
}

Public Member Functions

 MinitaurLeg (Motor *M0, Motor *M1)
 Declare the leg based on the consituent motors.
 
float getSpeed (float bodyPitch)
 Return forward speed. More...
 
void getToeForce (float &ur, float &uth)
 Get force at the toe. More...
 
void getToeForceXZ (float bodyPitch, bool bRight, float &ux, float &uz)
 Get toe forces in N in absolute coords. More...
 
- Public Member Functions inherited from AbstractMotor< 2 >
virtual void physicalToAbstract (const float in[N], float out[N])=0
 Transformation for forces at the toe to joint torques. More...
 
virtual void abstractToPhysical (const float in[N], float out[N])=0
 Forward kinematics. More...
 
void enable (bool flag)
 Enables all the motors in this "leg". More...
 
float getPosition (int i)
 Returns the ith toe position coordinate. More...
 
virtual float getPosition ()
 Get position of 0th coordinate. More...
 
float getVelocity (int i)
 Returns the ith toe coordinate velocity. More...
 
virtual float getVelocity ()
 Get velocity of 0th coordinate. More...
 
float getOpenLoop (int i)
 Get the openloop value for the ith coordinate; useful when using setPosition(int, float) More...
 
virtual float getOpenLoop ()
 Get open loop value of 0th coordinate. More...
 
void setOpenLoop (int i, float val)
 Set open loop command to coordinate i. More...
 
virtual void setOpenLoop (float val)
 Set open loop value for 0th coordinate. More...
 
void setGain (int i, float Kp, float Kd)
 Set PD gains for coordinate i. More...
 
void setPosition (int i, float setpoint)
 Set position setpoint for coordinate i, and change to position control mode. More...
 
virtual void setPosition (float pos)
 Set position for 0th coordinate. More...
 
void update ()
 This should be called at a more or less fixed rate (once per iteration) More...
 

Static Public Attributes

static bool useLengths = false
 If true, use the exact leg kinematics, and the extension coordinate is in length units. If false, use the mean angle as a proxy for extension (between 0 and PI).
 
static float l1 = 0.1
 Upper and lower link lengths. More...
 

Inherits AbstractMotor< 2 >.

Member Function Documentation

float MinitaurLeg::getSpeed ( float  bodyPitch)

Return forward speed.

Parameters
bodyPitchPitch angle of the body (required to figure out absolute leg angle)
Returns
Speed in m/s
void MinitaurLeg::getToeForce ( float &  ur,
float &  uth 
)

Get force at the toe.

The lengths MinitaurLeg::l1 and MinitaurLeg::l2 need to be correct, and also Motor::setTorqueEstParams needs to have be called for this to work.

Parameters
urRadial force in N. This is an output parameter (declare before this function)
uthTangential torque in N-m. This is an output parameter (declare before this function)
void MinitaurLeg::getToeForceXZ ( float  bodyPitch,
bool  bRight,
float &  ux,
float &  uz 
)

Get toe forces in N in absolute coords.

The lengths MinitaurLeg::l1 and MinitaurLeg::l2 need to be correct, and also Motor::setTorqueEstParams needs to have be called for this to work.

Parameters
bodyPitchpitch such that > 0 when leaned forward
bRighttrue if this is a right leg
uxReturns horizontal force in N. It is >0 if leg is pushed "back"
uzReturns vertical force in N. It is >0 if leg is pushed "up"

Member Data Documentation

float MinitaurLeg::l1 = 0.1
static

Upper and lower link lengths.

Copyright (C) Ghost Robotics - All Rights Reserved Unauthorized copying of this file, via any medium is strictly prohibited Proprietary and confidential Written by Avik De avik@.nosp@m.ghos.nosp@m.trobo.nosp@m.tics.nosp@m..io


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