Koduino
Public Member Functions | List of all members
AbstractMotor< N > Class Template Referenceabstract

Class for coordinating N motors in parallel. More...

#include <AbstractMotor.h>

Detailed Description

template<int N>
class AbstractMotor< N >

Class for coordinating N motors in parallel.

Template Parameters
Nnumber of motors to be coordinated

Description of multi-DOF motor coordination

The AbstractMotor base class is useful for coordinating multi-DOF appendages. Some useful derived classes are MinitaurLeg, SagittalPair, etc.

To use these classes:

  1. Each motor needs to be intialized (by BlCon34::init(), DxlMotor::init(), etc.) even though they are being coordinated together, just as in step 1 in the MotorController help page
  2. Call the constructor MinitaurLeg::MinitaurLeg() (or whichever AbstractMotor -derived class) with pointers to constituent Motor s
  3. Set the direction and zero of each Motor object first (do this before applying power)
  4. Call AbstractMotor::enable() (or on derived class)
  5. As in the Motor class, AbstractMotor::setOpenLoop(), AbstractMotor::setGain() and AbstractMotor::setPosition() exist, but they have a new first argument. The first argument represents the end-effector coordinate. For example, in MinitaurLeg, the first argument can be EXTENSION (defined as 0) or ANGLE (defined as 1).
  6. Call AbstractMotor::setOpenLoop() with first argument in (0, 1, ...) indicating the end-effector coordinate, and second argument between -1 and 1 to spin freely
  7. Call AbstractMotor::setGain() and AbstractMotor::setPosition() to command a position
  8. Call AbstractMotor::getPosition() or AbstractMotor::getVelocity() to get back data
  9. AbstractMotor::update() must be called frequently (don't call Motor::update() on the constituent motors)

An example for MinitaurLeg is found on its help page.

Creating a new multi-DOF appendage (derived class)

  1. Implement forward kinematics in AbstractMotor::physicalToAbstract
  2. Implement mapping of end effector forces to joint torques in AbstractMotor::abstractToPhysical

Public Member Functions

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...
 
float getVelocity (int i)
 Returns the ith toe coordinate velocity. More...
 
float getOpenLoop (int i)
 Get the openloop value for the ith coordinate; useful when using setPosition(int, float) More...
 
void setOpenLoop (int i, float val)
 Set open loop command to coordinate i. 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 float getPosition ()
 Get position of 0th coordinate. More...
 
virtual float getVelocity ()
 Get velocity of 0th coordinate. More...
 
virtual float getOpenLoop ()
 Get open loop value of 0th coordinate. More...
 
virtual void setOpenLoop (float val)
 Set open loop value for 0th coordinate. 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...
 

Member Function Documentation

template<int N>
virtual void AbstractMotor< N >::abstractToPhysical ( const float  in[N],
float  out[N] 
)
pure virtual

Forward kinematics.

Parameters
inJoint angles
outToe position
template<int N>
void AbstractMotor< N >::enable ( bool  flag)
inline

Enables all the motors in this "leg".

Parameters
flagtrue enables, false disables
template<int N>
float AbstractMotor< N >::getOpenLoop ( int  i)
inline

Get the openloop value for the ith coordinate; useful when using setPosition(int, float)

See also
Motor::getOpenLoop()
template<int N>
virtual float AbstractMotor< N >::getOpenLoop ( )
inlinevirtual

Get open loop value of 0th coordinate.

See also
getOpenLoop(int)
template<int N>
float AbstractMotor< N >::getPosition ( int  i)
inline

Returns the ith toe position coordinate.

Unlike Motor::getPosition(), the AbstractMotor::getPosition() doesn't actually read sensors, but returns the value stored from the last time Motor::update() was called.

Parameters
iith entry in the forward kinematics as specified in abstractToPhysical()
Returns
Position in physical units
template<int N>
virtual float AbstractMotor< N >::getPosition ( )
inlinevirtual

Get position of 0th coordinate.

See also
getPosition(int)
template<int N>
float AbstractMotor< N >::getVelocity ( int  i)
inline

Returns the ith toe coordinate velocity.

Parameters
iith entry in the forward kinematics as specified in abstractToPhysical()
Returns
Velocity in physical units
template<int N>
virtual float AbstractMotor< N >::getVelocity ( )
inlinevirtual

Get velocity of 0th coordinate.

See also
getVelocity(int)
template<int N>
virtual void AbstractMotor< N >::physicalToAbstract ( const float  in[N],
float  out[N] 
)
pure virtual

Transformation for forces at the toe to joint torques.

To be overridden: coordinate transforms

Parameters
inToe forces
outJoint torques
template<int N>
void AbstractMotor< N >::setGain ( int  i,
float  Kp,
float  Kd 
)
inline

Set PD gains for coordinate i.

Parameters
KpP gain
KdD gain (optional argument)
template<int N>
void AbstractMotor< N >::setOpenLoop ( int  i,
float  val 
)
inline

Set open loop command to coordinate i.

Like Motor::setOpenLoop(), the actual communication happens in AbstractMotor::update()

Parameters
valBetween -1 and 1
template<int N>
virtual void AbstractMotor< N >::setOpenLoop ( float  val)
inlinevirtual

Set open loop value for 0th coordinate.

See also
setOpenLoop(int, float)
template<int N>
void AbstractMotor< N >::setPosition ( int  i,
float  setpoint 
)
inline

Set position setpoint for coordinate i, and change to position control mode.

Parameters
setpointSetpoint in units of coordinate i (PD control in end-effector space)
template<int N>
virtual void AbstractMotor< N >::setPosition ( float  pos)
inlinevirtual

Set position for 0th coordinate.

See also
setPosition(int, float)
template<int N>
void AbstractMotor< N >::update ( )
inline

This should be called at a more or less fixed rate (once per iteration)

Don't call Motor::update() on the constituent motors


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