Koduino
Public Member Functions | Static Public Attributes | List of all members
Motor Class Referenceabstract

Base single-motor class. More...

#include <Motor.h>

Detailed Description

Base single-motor class.

Implements enable/disable, setting open-loop commands, PD position control, gear ratio. This class is an abstract base class, and derived classes need to implement the low-level communication with the motor driver.

Public Member Functions

virtual void enable (bool flag)=0
 Enable the motor. More...
 
virtual float getRawPosition ()=0
 Raw position read from the motor driver. More...
 
virtual void sendOpenLoop (float val)=0
 Communicate a raw PWM to the motor controller. More...
 
void init (float zero, int8_t direction, float gearRatio)
 Initialize motor properties. More...
 
float getPosition ()
 Get position after direction and zero are taken into account. More...
 
float getVelocity ()
 Get motor velocity after direction and zero are taken into account. More...
 
float getOpenLoop ()
 Get the PWM duty cycle commanded to the motor. More...
 
void setTorqueEstParams (float Kt, float res, float Vsource, float curLim)
 Details for torque estimate in getTorque(). Not used elsewhere. More...
 
float getTorque ()
 Returns an estimate of torque assuming quasistatic. More...
 
void setOpenLoop (float val)
 Set an open loop PWM command for the motor. More...
 
void setGain (float Kp, float Kd)
 Set gain for position control. More...
 
void setGain (float Kp)
 Set P-gain for position control (D-gain is set to 0) More...
 
void setPosition (float setpoint)
 Set a desired position for the motor in radians. More...
 
float update ()
 Function that communicates with the motor controller (including getting position, commanding PWM) More...
 
void resetOffset ()
 Run this after you are sure there is non-garbage rawPosition data.
 

Static Public Attributes

static int updateRate = 1000
 Set expected rate (Hz) at which update() will be called. More...
 
static float velSmooth = 0.8
 Set smoothing factor for getVelocity() (0 is no smoothing, 1 never updates)
 

Inherited by BlCon34.

Member Function Documentation

virtual void Motor::enable ( bool  flag)
pure virtual

Enable the motor.

Must be implemented in derived classes

Parameters
flagtrue to enable, false to disable

Implemented in BlCon34.

float Motor::getOpenLoop ( )
inline

Get the PWM duty cycle commanded to the motor.

Useful to record input when getPosition() is used

Returns
Commanded PWM in [-1, 1]
float Motor::getPosition ( )

Get position after direction and zero are taken into account.

Returns
Position in radians between -pi and pi
virtual float Motor::getRawPosition ( )
pure virtual

Raw position read from the motor driver.

This is before the direction/zero are applied. The user should call getPosition()

Returns
Raw position in [0, 2pi]

Implemented in BlCon34.

float Motor::getTorque ( )
inline

Returns an estimate of torque assuming quasistatic.

Need to call setTorqueEstParams() beforhand

Returns
Estimate of torque in Nm
float Motor::getVelocity ( )
inline

Get motor velocity after direction and zero are taken into account.

Returns
Velocity in rad/s
void Motor::init ( float  zero,
int8_t  direction,
float  gearRatio 
)

Initialize motor properties.

Parameters
zeroThe zero angle (in terms of getRawPosition())
directionOne of +1 and -1 (reverses in which direction positions increase)
gearRatioDefault is 1.0 (direct drive)
virtual void Motor::sendOpenLoop ( float  val)
pure virtual

Communicate a raw PWM to the motor controller.

Must be implemented in derived classes. The user should call setOpenLoop()

Parameters
valRaw PWM in [-1, 1]

Implemented in BlCon34.

void Motor::setGain ( float  Kp,
float  Kd 
)

Set gain for position control.

This must be called when setPosition() is used

Parameters
KpP-gain (in units of PWM / rad)
KdD-gain (in units of PWM / (rad/s))
void Motor::setGain ( float  Kp)
inline

Set P-gain for position control (D-gain is set to 0)

This must be called when setPosition() is used

Parameters
KpP-gain (in units of PWM / rad)
void Motor::setOpenLoop ( float  val)

Set an open loop PWM command for the motor.

These commands are only sent by update()

Parameters
valCommanded PWM in [-1, 1]
void Motor::setPosition ( float  setpoint)

Set a desired position for the motor in radians.

setGain() needs to be called as well

Parameters
setpointDesired position in radians (relative to direction and zero set by Motor::init())
void Motor::setTorqueEstParams ( float  Kt,
float  res,
float  Vsource,
float  curLim 
)

Details for torque estimate in getTorque(). Not used elsewhere.

Parameters
Ktin Nm/A
resin Ohms
Vsourcein Volts
float Motor::update ( )

Function that communicates with the motor controller (including getting position, commanding PWM)

This should be called at a more or less fixed rate (once per iteration). Change Motor::updateRate to the expected frequency that update() will be called.

Returns
Returns the corrected raw PWM sent to the motor controller

Member Data Documentation

int Motor::updateRate = 1000
static

Set expected rate (Hz) at which update() will be called.

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: