Koduino
|
Class for coordinating two parallel coaxial motors in the Minitaur config. More...
#include <MinitaurLeg.h>
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.
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.
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),
ANGLE
coordinate always refers to α - π in radians (where the front of the robot is to the right in the figure above). I.e., when the leg is vertically pointing down, ANGLE
is 0, if it sweeps back, ANGLE
is positive, etc.EXTENSION
coordinate either refers to β in radians from 0 (fully retracted) to π (fully extended)EXTENSION
coordinate refers to r in meters.To use a MinitaurLeg in your code, follow the usage steps in the AbstractMotor help page. Additionally,
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 >.
float MinitaurLeg::getSpeed | ( | float | bodyPitch | ) |
Return forward speed.
bodyPitch | Pitch angle of the body (required to figure out absolute leg angle) |
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.
ur | Radial force in N. This is an output parameter (declare before this function) |
uth | Tangential 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.
bodyPitch | pitch such that > 0 when leaned forward |
bRight | true if this is a right leg |
ux | Returns horizontal force in N. It is >0 if leg is pushed "back" |
uz | Returns vertical force in N. It is >0 if leg is pushed "up" |
|
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@ ghos trobo tics .io