Motor class. More...
#include <kmlMotBase.h>
Public Member Functions | |
bool | checkAngleInRange (double angle) |
check limits in encoder values | |
bool | checkEncoderInRange (int encoder) |
void | dec (int dif, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS) |
Decrements the motor specified by an index postion in encoder units. | |
void | decDegrees (double dif, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS) |
Decrements the motor specified by an index postion in degrees. | |
const TMotAPS * | GetAPS () |
bool | GetBlocked () |
Get the value of the blocked property. | |
const TMotCLB * | GetCLB () |
const TMotDYL * | GetDYL () |
int | GetEncoderMaxPos () |
Returns the max Position of the Encoder. | |
int | GetEncoderMinPos () |
Returns the min Position of the Encoder. | |
int | GetEncoderRange () |
Returns Encoder Range of the Encoder. | |
int | GetEncoderTolerance () |
bool | GetFreedom () |
Get the value of the freedom property. | |
const TMotGNL * | GetGNL () |
const TMotInit * | GetInitialParameters () |
void | getParameterOrLimit (int subcommand, byte *R1, byte *R2, byte *R3) |
const TMotPVP * | GetPVP () |
const TMotSCP * | GetSCP () |
const TMotSFW * | GetSFW () |
const TMotTPS * | GetTPS () |
void | inc (int dif, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS) |
Increments the motor specified by an index postion in encoder units. | |
void | incDegrees (double dif, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS) |
Increments the motor specified by an index postion in degrees. | |
bool | init (CKatBase *_own, const TMotDesc _motDesc, CCplBase *protocol) |
void | mov (int tar, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS) |
Moves the motor specified by an index to a given target position in encoder units. | |
void | movDegrees (double tar, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS) |
Moves the motor specified by an index to a given target position in degrees. | |
void | recvPVP () |
receive data | |
void | recvSFW () |
receive data | |
void | resetBlocked () |
unblock the motor. | |
void | sendAPS (const TMotAPS *_aps) |
send data | |
void | sendSpline (short targetPosition, short duration, short p1, short p2, short p3, short p4) |
void | sendTPS (const TMotTPS *_tps) |
send data | |
void | setAccelerationLimit (short acceleration) |
void | setCalibrated (bool calibrated) |
void | setCalibrationParameters (bool doCalibration, short order, TSearchDir direction, TMotCmdFlg motorFlagAfter, int encoderPositionAfter) |
void | setControllerParameters (byte kSpeed, byte kPos, byte kI) |
void | setCrashLimit (int limit) |
void | setCrashLimitLinear (int limit_lin) |
Set the crash limit linear. | |
void | setDYL (TMotDYL _dyl) |
void | setInitialParameters (double angleOffset, double angleRange, int encodersPerCycle, int encoderOffset, int rotationDirection) |
void | setPositionCollisionLimit (int limit) |
Set the collision limit. | |
void | setPwmLimits (byte maxppwm, byte maxnpwm) |
void | setSCP (TMotSCP _scp) |
void | setSpeedCollisionLimit (int limit) |
Set the collision limit. | |
void | setSpeedLimit (short velocity) |
void | setSpeedLimits (short positiveVelocity, short negativeVelocity) |
Set speed limits. | |
void | setTolerance (int tolerance) |
void | waitForMotor (int tar, int encTolerance=100, short mode=0, int waitTimeout=TM_ENDLESS) |
Waits until the Motor has reached the given targen position. | |
virtual | ~CMotBase () |
Protected Attributes | |
TMotCLB | _calibrationParameters |
calibration structure | |
TMotENL | _encoderLimits |
motor limits in encoder values | |
TMotInit | _initialParameters |
TMotAPS | aps |
actual position | |
bool | blocked |
true if the motor was blocked due to a crash of the robot | |
TMotDYL | dyl |
dynamic limits | |
bool | freedom |
if it is set, it will move on a parallel movement | |
TMotGNL | gnl |
motor generals | |
CCplBase * | protocol |
protocol interface | |
TMotPVP | pvp |
reading motor parameters | |
TMotSCP | scp |
static controller parameters | |
TMotSFW | sfw |
slave firmware | |
TMotTPS | tps |
target position | |
Friends | |
class | CKatBase |
Motor class.
This class allows to control one motor; to control a motor it has to be initialized by using the init function. And the usage the internal allocated resources should be deallocated by using the 'free' method.
Definition at line 220 of file kmlMotBase.h.
virtual CMotBase::~CMotBase | ( | ) | [inline, virtual] |
Definition at line 265 of file kmlMotBase.h.
bool CMotBase::checkAngleInRange | ( | double | angle | ) |
check limits in encoder values
Definition at line 362 of file kmlMotBase.cpp.
bool CMotBase::checkEncoderInRange | ( | int | encoder | ) |
Definition at line 365 of file kmlMotBase.cpp.
void CMotBase::dec | ( | int | dif, |
bool | wait = false , |
||
int | tolerance = 100 , |
||
long | timeout = TM_ENDLESS |
||
) |
Decrements the motor specified by an index postion in encoder units.
Definition at line 375 of file kmlMotBase.cpp.
void CMotBase::decDegrees | ( | double | dif, |
bool | wait = false , |
||
int | tolerance = 100 , |
||
long | timeout = TM_ENDLESS |
||
) |
Decrements the motor specified by an index postion in degrees.
Definition at line 434 of file kmlMotBase.cpp.
const TMotAPS* CMotBase::GetAPS | ( | ) | [inline] |
Definition at line 242 of file kmlMotBase.h.
bool CMotBase::GetBlocked | ( | ) | [inline] |
Get the value of the blocked property.
Definition at line 259 of file kmlMotBase.h.
const TMotCLB* CMotBase::GetCLB | ( | ) | [inline] |
Definition at line 248 of file kmlMotBase.h.
const TMotDYL* CMotBase::GetDYL | ( | ) | [inline] |
Definition at line 245 of file kmlMotBase.h.
int CMotBase::GetEncoderMaxPos | ( | ) | [inline] |
Returns the max Position of the Encoder.
Definition at line 253 of file kmlMotBase.h.
int CMotBase::GetEncoderMinPos | ( | ) | [inline] |
Returns the min Position of the Encoder.
Definition at line 252 of file kmlMotBase.h.
int CMotBase::GetEncoderRange | ( | ) | [inline] |
Returns Encoder Range of the Encoder.
Definition at line 254 of file kmlMotBase.h.
int CMotBase::GetEncoderTolerance | ( | ) | [inline] |
Definition at line 251 of file kmlMotBase.h.
bool CMotBase::GetFreedom | ( | ) | [inline] |
Get the value of the freedom property.
Definition at line 257 of file kmlMotBase.h.
const TMotGNL* CMotBase::GetGNL | ( | ) | [inline] |
Definition at line 241 of file kmlMotBase.h.
const TMotInit* CMotBase::GetInitialParameters | ( | ) | [inline] |
Definition at line 250 of file kmlMotBase.h.
void CMotBase::getParameterOrLimit | ( | int | subcommand, |
byte * | R1, | ||
byte * | R2, | ||
byte * | R3 | ||
) |
Get parameters or limits
subcommand | 255-249;245, see katana user manual chapter 8 firmware commands for details |
R1 | pointer to store first byte of answer |
R2 | pointer to store second byte of answer |
R3 | pointer to store third byte of answer |
Definition at line 274 of file kmlMotBase.cpp.
const TMotPVP* CMotBase::GetPVP | ( | ) | [inline] |
Definition at line 246 of file kmlMotBase.h.
const TMotSCP* CMotBase::GetSCP | ( | ) | [inline] |
Definition at line 244 of file kmlMotBase.h.
const TMotSFW* CMotBase::GetSFW | ( | ) | [inline] |
Definition at line 247 of file kmlMotBase.h.
const TMotTPS* CMotBase::GetTPS | ( | ) | [inline] |
Definition at line 243 of file kmlMotBase.h.
void CMotBase::inc | ( | int | dif, |
bool | wait = false , |
||
int | tolerance = 100 , |
||
long | timeout = TM_ENDLESS |
||
) |
Increments the motor specified by an index postion in encoder units.
Definition at line 370 of file kmlMotBase.cpp.
void CMotBase::incDegrees | ( | double | dif, |
bool | wait = false , |
||
int | tolerance = 100 , |
||
long | timeout = TM_ENDLESS |
||
) |
Increments the motor specified by an index postion in degrees.
Definition at line 427 of file kmlMotBase.cpp.
bool CMotBase::init | ( | CKatBase * | _own, |
const TMotDesc | _motDesc, | ||
CCplBase * | protocol | ||
) |
Definition at line 20 of file kmlMotBase.cpp.
void CMotBase::mov | ( | int | tar, |
bool | wait = false , |
||
int | tolerance = 100 , |
||
long | timeout = TM_ENDLESS |
||
) |
Moves the motor specified by an index to a given target position in encoder units.
Definition at line 380 of file kmlMotBase.cpp.
void CMotBase::movDegrees | ( | double | tar, |
bool | wait = false , |
||
int | tolerance = 100 , |
||
long | timeout = TM_ENDLESS |
||
) |
Moves the motor specified by an index to a given target position in degrees.
Definition at line 441 of file kmlMotBase.cpp.
void CMotBase::recvPVP | ( | ) |
receive data
Definition at line 90 of file kmlMotBase.cpp.
void CMotBase::recvSFW | ( | ) |
receive data
Definition at line 109 of file kmlMotBase.cpp.
void CMotBase::resetBlocked | ( | ) |
unblock the motor.
Definition at line 35 of file kmlMotBase.cpp.
void CMotBase::sendAPS | ( | const TMotAPS * | _aps | ) |
send data
Definition at line 53 of file kmlMotBase.cpp.
void CMotBase::sendSpline | ( | short | targetPosition, |
short | duration, | ||
short | p1, | ||
short | p2, | ||
short | p3, | ||
short | p4 | ||
) |
Send one spline to the motor
duration | Duration has to be given in 10ms units |
Definition at line 299 of file kmlMotBase.cpp.
void CMotBase::sendTPS | ( | const TMotTPS * | _tps | ) |
send data
Definition at line 73 of file kmlMotBase.cpp.
void CMotBase::setAccelerationLimit | ( | short | acceleration | ) |
Set the acceleration limits
Definition at line 149 of file kmlMotBase.cpp.
void CMotBase::setCalibrated | ( | bool | calibrated | ) |
Definition at line 353 of file kmlMotBase.cpp.
void CMotBase::setCalibrationParameters | ( | bool | doCalibration, |
short | order, | ||
TSearchDir | direction, | ||
TMotCmdFlg | motorFlagAfter, | ||
int | encoderPositionAfter | ||
) |
Definition at line 343 of file kmlMotBase.cpp.
void CMotBase::setControllerParameters | ( | byte | kSpeed, |
byte | kPos, | ||
byte | kI | ||
) |
Set the controller parameters
Definition at line 186 of file kmlMotBase.cpp.
void CMotBase::setCrashLimit | ( | int | limit | ) |
Set the crash limit
Definition at line 206 of file kmlMotBase.cpp.
void CMotBase::setCrashLimitLinear | ( | int | limit_lin | ) |
Set the crash limit linear.
Definition at line 224 of file kmlMotBase.cpp.
void CMotBase::setDYL | ( | TMotDYL | _dyl | ) | [inline] |
Definition at line 280 of file kmlMotBase.h.
void CMotBase::setInitialParameters | ( | double | angleOffset, |
double | angleRange, | ||
int | encodersPerCycle, | ||
int | encoderOffset, | ||
int | rotationDirection | ||
) |
Definition at line 324 of file kmlMotBase.cpp.
void CMotBase::setPositionCollisionLimit | ( | int | limit | ) |
Set the collision limit.
Definition at line 259 of file kmlMotBase.cpp.
void CMotBase::setPwmLimits | ( | byte | maxppwm, |
byte | maxnpwm | ||
) |
Set the PWM limits (for the drive controller)
Definition at line 165 of file kmlMotBase.cpp.
void CMotBase::setSCP | ( | TMotSCP | _scp | ) | [inline] |
Definition at line 279 of file kmlMotBase.h.
void CMotBase::setSpeedCollisionLimit | ( | int | limit | ) |
Set the collision limit.
Definition at line 243 of file kmlMotBase.cpp.
void CMotBase::setSpeedLimit | ( | short | velocity | ) | [inline] |
Definition at line 331 of file kmlMotBase.h.
void CMotBase::setSpeedLimits | ( | short | positiveVelocity, |
short | negativeVelocity | ||
) |
Set speed limits.
Definition at line 130 of file kmlMotBase.cpp.
void CMotBase::setTolerance | ( | int | tolerance | ) |
Definition at line 358 of file kmlMotBase.cpp.
void CMotBase::waitForMotor | ( | int | tar, |
int | encTolerance = 100 , |
||
short | mode = 0 , |
||
int | waitTimeout = TM_ENDLESS |
||
) |
Waits until the Motor has reached the given targen position.
Definition at line 396 of file kmlMotBase.cpp.
friend class CKatBase [friend] |
Definition at line 222 of file kmlMotBase.h.
TMotCLB CMotBase::_calibrationParameters [protected] |
calibration structure
Definition at line 233 of file kmlMotBase.h.
TMotENL CMotBase::_encoderLimits [protected] |
motor limits in encoder values
Definition at line 234 of file kmlMotBase.h.
TMotInit CMotBase::_initialParameters [protected] |
Definition at line 235 of file kmlMotBase.h.
TMotAPS CMotBase::aps [protected] |
actual position
Definition at line 227 of file kmlMotBase.h.
bool CMotBase::blocked [protected] |
true if the motor was blocked due to a crash of the robot
Definition at line 237 of file kmlMotBase.h.
TMotDYL CMotBase::dyl [protected] |
dynamic limits
Definition at line 230 of file kmlMotBase.h.
bool CMotBase::freedom [protected] |
if it is set, it will move on a parallel movement
Definition at line 236 of file kmlMotBase.h.
TMotGNL CMotBase::gnl [protected] |
motor generals
Definition at line 226 of file kmlMotBase.h.
CCplBase* CMotBase::protocol [protected] |
protocol interface
Definition at line 262 of file kmlMotBase.h.
TMotPVP CMotBase::pvp [protected] |
reading motor parameters
Definition at line 231 of file kmlMotBase.h.
TMotSCP CMotBase::scp [protected] |
static controller parameters
Definition at line 229 of file kmlMotBase.h.
TMotSFW CMotBase::sfw [protected] |
slave firmware
Definition at line 232 of file kmlMotBase.h.
TMotTPS CMotBase::tps [protected] |
target position
Definition at line 228 of file kmlMotBase.h.