00001
00002
00003
00004
00005
00006 #ifndef __DXLGENERIC_H_INCLUDED__
00007 #define __DXLGENERIC_H_INCLUDED__
00008 #include "CDxlCom.h"
00009 #include "CDxlConfig.h"
00010 #include "CDxlGroup.h"
00011 #include <threemxl/platform/io/logging/Log2.h>
00012
00013 #include <iostream>
00014 #include <iomanip>
00015
00016 #define PACKET_RETRY_FACTOR 1
00017
00018
00019 class CDxlConfig;
00020 class CDxlGroup;
00021
00023 typedef struct
00024 {
00025 uint16_t time;
00026 float pwm,
00027 current,
00028 voltage,
00029 desired,
00030 actual;
00031 } __attribute__((packed)) TMxlLogEntry;
00032
00033 inline std::ostream &operator<<(std::ostream &outs, const TMxlLogEntry &obj)
00034 {
00035 outs << std::fixed
00036 << std::setw(8) << obj.time << " "
00037 << std::setw(8) << obj.pwm << " "
00038 << std::setw(8) << std::setprecision(3) << obj.current << " "
00039 << std::setw(8) << std::setprecision(3) << obj.voltage << " "
00040 << std::setw(8) << std::setprecision(3) << obj.desired << " "
00041 << std::setw(8) << std::setprecision(3) << obj.actual
00042 << std::resetiosflags(std::ios_base::floatfield);
00043
00044 return outs;
00045 }
00046
00047 typedef std::vector<TMxlLogEntry> TMxlLog;
00048
00050
00055 class CDxlGeneric: public CDxlCom
00056 {
00057 protected:
00058 CDxlGroup* mpGroup;
00059 int mID;
00060 int mRetlevel;
00061 CLog2 mLog;
00062
00063 public:
00064 CDxlGeneric(): mLog("CDxlGeneric")
00065 {
00066
00067
00068 mpGroup = NULL;
00069 }
00070 virtual ~CDxlGeneric() {};
00071
00073
00078 int readData(BYTE startingAddress, BYTE dataLength, BYTE *data);
00079
00081
00087 int writeData(BYTE startingAddress, BYTE dataLength, BYTE *data, bool shouldSyncWrite=false);
00088
00090 int action();
00091
00093 int reset();
00094
00096
00097 int ping();
00098
00100
00104 virtual int getID()=0;
00105
00107
00111 virtual void setGroup(CDxlGroup* group) { mpGroup = group;}
00112
00114
00118 virtual void setConfig(CDxlConfig* config) {};
00119
00121
00122 virtual void setSerialPort(LxSerial* serialPort) {};
00123
00125
00129 virtual int init(bool sendConfigToMotor=true) {mLogWarningLn("init function not implemented"); return false;};
00130
00132
00133 virtual void setPositiveDirection(bool clockwiseIsPositive) {mLogWarningLn("setPositiveDirection function not implemented");};
00134
00136
00137 virtual void setNullAngle(double nullAngle) {mLogWarningLn("setNullAngle function not implemented");};
00138
00140
00144 virtual int setPos(double pos, bool shouldSyncWrite=false) {mLogWarningLn("setPos/1 function not implemented"); return false;};
00145
00147
00152 virtual int setPos(double pos, double absSpeed, bool shouldSyncWrite=false) {mLogWarningLn("setPos/2 function not implemented"); return false;};
00153
00155
00161 virtual int setPos(double pos, double absSpeed, double acceleration, bool shouldSyncWrite=false) {mLogWarningLn("setPos/3 function not implemented"); return false;};
00162
00164
00169 virtual int setLinearPos(double pos, bool shouldSyncWrite=false) {mLogWarningLn("setPosLinear/1 function not implemented"); return false;};
00170
00172
00177 virtual int setLinearPos(double pos, double absSpeed, bool shouldSyncWrite=false) {mLogWarningLn("setPosLinear/2 function not implemented"); return false;};
00178
00180
00186 virtual int setLinearPos(double pos, double absSpeed, double acceleration, bool shouldSyncWrite=false) {mLogWarningLn("setPosLinear/3 function not implemented"); return false;};
00187
00189
00193 virtual int setSpeed(double speed, bool shouldSyncWrite=false) {mLogWarningLn("setSpeed function not implemented"); return false;};
00194
00196
00200 virtual int setLinearSpeed(double speed, bool shouldSyncWrite=false) {mLogWarningLn("setLinearSpeed function not implemented"); return false;};
00201
00203
00207 virtual int setAcceleration(double acceleration, bool shouldSyncWrite=false) {mLogWarningLn("setAcceleration function not implemented"); return false;};
00208
00210
00214 virtual int setLinearAcceleration(double acceleration, bool shouldSyncWrite=false) {mLogWarningLn("setLinearAcceleration function not implemented"); return false;};
00215
00217
00221 virtual int setTorque(double torque, bool shouldSyncWrite=false) {mLogWarningLn("setTorque function not implemented"); return false;};
00222
00224
00228 virtual int setCurrent(double current, bool shouldSyncWrite=false) {mLogWarningLn("setCurrent function not implemented"); return false;};
00229
00231
00235 virtual int setPWM(double pwm, bool shouldSyncWrite=false) {mLogWarningLn("setPWM function not implemented"); return false;};
00236
00238
00246 virtual int setPosSpeedTorquePPosDPos(double pos, double speed, double torque, int pPos, int dPos, bool shouldSyncWrite=false) {mLogWarningLn("setPosSpeedTorquePPosDPos function not implemented"); return false;};
00247
00249
00258 virtual int setPIDCurrent(double p, double d, double i, double i_limit, bool shouldSyncWrite=false) {mLogWarningLn("setPIDCurrent function not implemented"); return false;};
00259
00261
00268 virtual int getPIDCurrent(double &p, double &d, double &i, double &i_limit) {mLogWarningLn("getPIDCurrent function not implemented"); return false;};
00269
00271
00280 virtual int setPIDPosition(double p, double d, double i, double i_limit, bool shouldSyncWrite=false) {mLogWarningLn("setPIDPosition function not implemented"); return false;};
00281
00283
00290 virtual int getPIDPosition(double &p, double &d, double &i, double &i_limit) {mLogWarningLn("getPIDPosition function not implemented"); return false;};
00291
00293
00302 virtual int setPIDSpeed(double p, double d, double i, double i_limit, bool shouldSyncWrite=false) {mLogWarningLn("setPIDSpeed function not implemented"); return false;};
00303
00305
00312 virtual int getPIDSpeed(double &p, double &d, double &i, double &i_limit) {mLogWarningLn("getPIDSpeed function not implemented"); return false;};
00313
00315
00324 virtual int setPIDTorque(double p, double d, double i, double i_limit, bool shouldSyncWrite=false) {mLogWarningLn("setPIDSpeed function not implemented"); return false;};
00325
00327
00334 virtual int getPIDTorque(double &p, double &d, double &i, double &i_limit) {mLogWarningLn("getPIDTorque function not implemented"); return false;};
00335
00337
00346 virtual int setPIDEnergy(double p, double d, double i, double i_limit, bool shouldSyncWrite=false) {mLogWarningLn("setPIDEnergy function not implemented"); return false;};
00347
00349
00356 virtual int getPIDEnergy(double &p, double &d, double &i, double &i_limit) {mLogWarningLn("getPIDEnergy function not implemented"); return false;};
00357
00359
00360 virtual int setRetlevel(const int returnlevel) {mLogWarningLn("setRetlevel function not implemented"); return false;};
00361
00363
00364 virtual int setBaudRateIndex(const BYTE baudRateIndex) {mLogWarningLn("setBaudRateIndex function not implemented"); return false;};
00365
00367
00368 virtual int setBaudRate(const int baudRate) {mLogWarningLn("setBaudRate function not implemented"); return false;};
00369
00371
00374 virtual int setReturnDelayTime(const int microsecondsReturnDelay) {mLogWarningLn("setReturnDelayTime function not implemented"); return false;};
00375
00377
00381 virtual int setInitialTorqueLimit(double absMaxTorque) {mLogWarningLn("setInitialTorqueLimit function not implemented"); return false;};
00382
00384
00385 virtual int setTorqueLimit(double absMaxTorque) {mLogWarningLn("setTorqueLimit function not implemented"); return false;};
00386
00388
00392 virtual int setAngleLimits(double lowerLimit, double upperLimit) {mLogWarningLn("setAngleLimits function not implemented"); return false;};
00393
00395
00399 virtual int setVoltageLimits(double minVoltage, double maxVoltage) {mLogWarningLn("setVoltageLimits function not implemented"); return false;};
00400
00402
00403 virtual int setTemperatureLimit(const int maxTemp) {mLogWarningLn("setTemperatureLimit function not implemented"); return false;};
00404
00406
00409 virtual int setAngleLowerLimit(double limit) {mLogWarningLn("setAngleLowerLimit function not implemented"); return false;};
00410
00412
00415 virtual int setAngleUpperLimit(double limit){mLogWarningLn("setAngleUpperLimit function not implemented"); return false;};
00416
00418
00423 virtual int setCompliance(BYTE complianceMargin, BYTE complianceSlope){mLogWarningLn("setCompliance function not implemented"); return false;};
00424
00426
00427 virtual int setPunch(WORD punch){mLogWarningLn("setPunch function not implemented"); return false;};
00428
00430
00431 virtual int setAlarmLEDMask(const BYTE mask){mLogWarningLn("setAlarmLEDMask function not implemented"); return false;};
00432
00434
00435 virtual int setOperatingMode(const BYTE mode){mLogWarningLn("setOperatingMode function not implemented"); return false;};
00436
00438
00439 virtual int setAlarmShutdownMask(const BYTE mask){mLogWarningLn("setAlarmShutdownMask function not implemented"); return false;};
00440
00442
00445 virtual int changeID(const int newID){mLogWarningLn("changeID function not implemented"); return false;};
00446
00448
00449 virtual int enableLED(int state){mLogWarningLn("enableLED function not implemented"); return false;};
00450
00452
00453 virtual int enableTorque(int state){mLogWarningLn("enableTorque function not implemented"); return false;};
00454
00456
00462 virtual int setEndlessTurnMode(bool enabled, bool shouldSyncWrite=false){mLogWarningLn("setEndlessTurnMode function not implemented"); return false;};
00463
00465
00469 virtual int setEndlessTurnTorque(double torqueRatio, bool shouldSyncWrite=false){mLogWarningLn("setEndlessTurnTorque function not implemented"); return false;};
00470
00472
00478 virtual int set3MxlMode(BYTE mxlMode, bool shouldSyncWrite = false){mLogWarningLn("set3MxlMode function not implemented"); return false;};
00479
00481
00482 virtual int setPositiveDirectionMotor(bool clockwiseIsPositive){mLogWarningLn("setPositiveDirectionMotor function not implemented"); return false;};
00483
00485
00486 virtual int setPositiveDirectionJoint(bool clockwiseIsPositive){mLogWarningLn("setPositiveDirectionJoint function not implemented"); return false;};
00487
00489
00490 virtual int setMotorOffset(double offset){mLogWarningLn("setMotorOffset function not implemented"); return false;};
00491
00493
00494 virtual int setJointOffset(double offset){mLogWarningLn("setJointOffset function not implemented"); return false;};
00495
00497
00498 virtual int setEncoderCountMotor(WORD encodercount){mLogWarningLn("setEncoderCountMotor function not implemented"); return false;};
00499
00501
00502 virtual int setEncoderCountJoint(WORD encodercount){mLogWarningLn("setEncoderCountJoint function not implemented"); return false;};
00503
00505
00506 virtual int setMotorConstant(WORD motorconstant){mLogWarningLn("setMotorConstant function not implemented"); return false;};
00507
00509
00510 virtual int setMaxPeakMotorCurrent(double current){mLogWarningLn("setMaxMotorPeakCurrent function not implemented"); return false;};
00511
00513
00514 virtual int setMaxContinuousMotorCurrent(double current){mLogWarningLn("setMaxMotorContinuousCurrent function not implemented"); return false;};
00515
00517
00518 virtual int setMotorWindingTimeConstant(double time){mLogWarningLn("setMotorWindingTimeConstant function not implemented"); return false;};
00519
00521
00522 virtual int setEncoderIndexLevelMotor(BYTE level){mLogWarningLn("setEncoderIndexLevelMotor function not implemented"); return false;};
00523
00525
00526 virtual int setWheelDiameter(double diameter){mLogWarningLn("setWheelDiameter function not implemented"); return false; };
00527
00529
00530 virtual int setGearboxRatioMotor(float gearboxratiomotor){mLogWarningLn("setGearboxRatioMotor function not implemented"); return false;};
00531
00533
00534 virtual int setGearboxRatioJoint(float gearboxratiojoint){mLogWarningLn("setGearboxRatioJoint function not implemented"); return false;};
00535
00537
00538 virtual int setWatchdogMode(BYTE watchdogmode){mLogWarningLn("setWatchdogMode function not implemented"); return false;};
00539
00541
00542 virtual int setWatchdogTime(BYTE watchdogtime){mLogWarningLn("setWatchdogTime function not implemented"); return false;};
00543
00545
00546 virtual int setWatchdogMultiplier(BYTE watchdogmultiplier){mLogWarningLn("setWatchdogMultiplier function not implemented"); return false;};
00547
00549
00550 virtual int setMaxUninitializedMotorCurrent(WORD maxcurrent){mLogWarningLn("setMaxUninitializedMotorCurrent function not implemented"); return false;};
00551
00553
00554 virtual int setMaxMotorCurrent(WORD maxcurrent){mLogWarningLn("setMaxMotorCurrent function not implemented"); return false;};
00555
00557
00558 virtual int setZeroLengthSpring(double parameterInRad){mLogWarningLn("setZeroLengthSpring function not implemented"); return false;};
00559
00561
00562 virtual int setSpringStiffness(double stiffness){mLogWarningLn("setSpringStiffness function not implemented"); return false;};
00563
00565
00566 virtual int setReferenceEnergy(double energy){mLogWarningLn("setReferenceEnergy function not implemented"); return false;};
00567
00569
00574 virtual int setSineFrequency(double frequency, bool shouldSyncWrite=false) {mLogWarningLn("setSineFrequency function not implemented"); return false;};
00575
00577
00583 virtual int setSineAmplitude(double amplitude, bool shouldSyncWrite=false) {mLogWarningLn("setSineAmplitude function not implemented"); return false;};
00584
00586
00592 virtual int setSinePhase(double phase, bool shouldSyncWrite=false) {mLogWarningLn("setSinePhase function not implemented"); return false;};
00593
00595
00599 virtual int setLogInterval(BYTE interval){mLogWarningLn("startLog function not implemented"); return false; };
00600
00602
00606 virtual int setSyncReadIndex(BYTE index){mLogWarningLn("setSyncReadIndex function not implemented"); return false; };
00607
00609
00610 virtual int getPos(){mLogWarningLn("getPos function not implemented"); return false;};
00611
00613
00614 virtual int getLinearPos(){mLogWarningLn("getLinearPos function not implemented"); return false;};
00615
00617
00618 virtual int getPosAndSpeed(){mLogWarningLn("getPosAndSpeed function not implemented"); return false;};
00619
00621
00622 virtual int getTemp(){mLogWarningLn("getTemp function not implemented"); return false;};
00623
00625
00626 virtual int getState(){mLogWarningLn("getState function not implemented"); return false;};
00627
00629
00633 virtual int getAngleLimits(){mLogWarningLn("getAngleLimits function not implemented"); return false;};
00634
00636
00637 virtual int getVoltage(){mLogWarningLn("getVoltage function not implemented"); return false;};
00638
00640
00641 virtual int getBusVoltage(){mLogWarningLn("getBusVoltage function not implemented"); return false;};
00642
00644
00645 virtual int getSensorVoltages(){mLogWarningLn("getSensorsVoltages function not implemented"); return false; };
00646
00648
00649 virtual int getCurrent(){mLogWarningLn("getCurrent function not implemented"); return false;};
00650
00652
00653 virtual int getTorque(){mLogWarningLn("getTorque function not implemented"); return false;};
00654
00656
00657 virtual int getTorquePosSpeed(){mLogWarningLn("getTorquePosSpeed function not implemented"); return false;};
00658
00660
00661 virtual int getAcceleration(){mLogWarningLn("getAcceleration function not implemented"); return false;};
00662
00664
00665 virtual int getLinearAcceleration(){mLogWarningLn("getLinearAcceleration function not implemented"); return false;};
00666
00668 virtual int getStatus(){mLogWarningLn("getStatus function not implemented"); return false;};
00669
00671
00672 virtual int getLog(){mLogWarningLn("getLog function not implemented"); return false;};
00673
00675 virtual int get3MxlMode(){mLogWarningLn("get3MxlMode function not implemented"); return false;};
00676
00678
00679 virtual double presentPos()=0;
00680
00682
00683 virtual double presentLinearPos()=0;
00684
00686
00687 virtual double presentSpeed()=0;
00688
00690
00691 virtual double presentAcceleration()=0;
00692
00694
00695 virtual double presentLinearAcceleration()=0;
00696
00698
00699 virtual double presentLoad()=0;
00700
00702
00703 virtual double presentVoltage()=0;
00704
00706
00707 virtual double presentBusVoltage()=0;
00708
00710
00711 virtual double presentCurrentADCVoltage()=0;
00712
00714
00715 virtual double presentAnalog1Voltage()=0;
00716
00718
00719 virtual double presentAnalog2Voltage()=0;
00720
00722
00723 virtual double presentAnalog3Voltage()=0;
00724
00726
00727 virtual double presentAnalog4Voltage()=0;
00728
00730
00731 virtual double presentTemp()=0;
00732
00734
00735 virtual double presentCurrent()=0;
00736
00738
00739 virtual double presentTorque()=0;
00740
00742
00746 virtual int presentStatus(){mLogWarningLn("presentStatus function not implemented"); return 0;};
00747
00749
00750 virtual bool presentMotorInitState() {mLogWarningLn("presentMotorInitState function not implemented"); return 0;};
00751
00753
00757 virtual WORD presentCWAngleLimit()=0;
00758
00760
00764 virtual WORD presentCCWAngleLimit()=0;
00765
00767
00768 virtual double presentAngleLowerLimit()=0;
00769
00771
00772 virtual double presentAngleUpperLimit()=0;
00773
00775
00776 virtual TMxlLog presentLog(){mLogWarningLn("presentLog function not implemented"); return TMxlLog();};
00777
00779
00780 virtual BYTE present3MxlMode(){mLogWarningLn("present3MxlMode function not implemented"); return 0;};
00781
00783
00786 virtual int printReport(FILE* fOut){mLogWarningLn("printReport function not implemented"); return false;};
00787
00789
00794 virtual int interpretControlData(BYTE address, BYTE length, BYTE *data){mLogWarningLn("interpretControlData function not implemented"); return false;};
00795 };
00796
00797
00798 #endif //__DXLGENERIC_H_INCLUDED__