Class for coordinating N motors in parallel.
More...
#include <AbstractMotor.h>
template<int N>
class AbstractMotor< N >
Class for coordinating N motors in parallel.
- Template Parameters
-
N | number 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:
- 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
- Call the constructor MinitaurLeg::MinitaurLeg() (or whichever AbstractMotor -derived class) with pointers to constituent Motor s
- Set the direction and zero of each Motor object first (do this before applying power)
- Call AbstractMotor::enable() (or on derived class)
- 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).
- Call AbstractMotor::setOpenLoop() with first argument in (0, 1, ...) indicating the end-effector coordinate, and second argument between -1 and 1 to spin freely
- Call AbstractMotor::setGain() and AbstractMotor::setPosition() to command a position
- Call AbstractMotor::getPosition() or AbstractMotor::getVelocity() to get back data
- 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)
- Implement forward kinematics in AbstractMotor::physicalToAbstract
- Implement mapping of end effector forces to joint torques in AbstractMotor::abstractToPhysical
template<int N>
virtual void AbstractMotor< N >::abstractToPhysical |
( |
const float |
in[N], |
|
|
float |
out[N] |
|
) |
| |
|
pure virtual |
Forward kinematics.
- Parameters
-
in | Joint angles |
out | Toe position |
Enables all the motors in this "leg".
- Parameters
-
flag | true enables, false disables |
Returns the ith toe coordinate velocity.
- Parameters
-
- Returns
- Velocity in physical units
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
-
in | Toe forces |
out | Joint torques |
Set PD gains for coordinate i.
- Parameters
-
Kp | P gain |
Kd | D gain (optional argument) |
Set position setpoint for coordinate i, and change to position control mode.
- Parameters
-
setpoint | Setpoint in units of coordinate i (PD control in end-effector space) |
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: