00001
00060 #ifndef CANOPEN_H
00061 #define CANOPEN_H
00062
00063 #include <iostream>
00064 #include <map>
00065 #include <vector>
00066 #include <string>
00067 #include <cstring>
00068 #include <chrono>
00069 #include <unordered_map>
00070 #include <functional>
00071 #include <cstdlib>
00072 #include <thread>
00073 #include <math.h>
00074 #include <libpcan.h>
00075 #include <utility>
00076 #include <fcntl.h>
00077 #include <stdint.h>
00078 #include <inttypes.h>
00079 #include "schunkErrors.h"
00080 #include <unordered_map>
00081
00082 namespace canopen{
00083
00084 extern std::chrono::milliseconds syncInterval;
00085 extern std::string baudRate;
00086
00087
00088
00089
00090
00091
00092
00093 static std::map<std::string, uint32_t> baudrates = {
00094 {"1M" , CAN_BAUD_1M},
00095 {"500K" , CAN_BAUD_500K},
00096 {"250K" , CAN_BAUD_250K},
00097 {"125K" , CAN_BAUD_125K},
00098 {"100K" , CAN_BAUD_100K},
00099 {"50K" , CAN_BAUD_50K},
00100 {"20K" , CAN_BAUD_20K},
00101 {"10K" , CAN_BAUD_10K},
00102 {"5K" , CAN_BAUD_5K}
00103 };
00104
00105
00106
00107
00108
00109 class Device{
00110
00111 private:
00112
00113 uint8_t CANid_;
00114 double conversion_factor_;
00115 double offset_;
00116 std::string NMTState_;
00117 std::string motorState_;
00118 std::string deviceFile_;
00119 std::string name_;
00120 std::string group_;
00121
00122 std::vector<char> manufacturer_sw_version_;
00123 std::vector<char> manufacturer_hw_version_;
00124 std::vector<char> manufacturer_device_name_;
00125
00126 std::vector<uint16_t> vendor_id_;
00127 std::vector<uint16_t> product_code_;
00128 uint16_t revision_number_;
00129
00130 std::string error_register_;
00131 std::string manufacturer_error_register_;
00132
00133 bool initialized_;
00134 bool nmt_init_;
00135 bool driveReferenced_;
00136 bool ip_mode_active_;
00137 bool homingError_;
00138 double actualPos_;
00139 double desiredPos_;
00140 double actualVel_;
00141 double desiredVel_;
00142 std::chrono::milliseconds timeStamp_msec_;
00143 std::chrono::microseconds timeStamp_usec_;
00144
00145 int8_t modes_of_operation_display_;
00146
00147 bool hardware_limit_positive_;
00148 bool hardware_limit_negative_;
00149
00150
00151 bool ready_switch_on_;
00152 bool switched_on_;
00153 bool op_enable_;
00154 bool fault_;
00155 bool volt_enable_;
00156 bool quick_stop_;
00157 bool switch_on_disabled_;
00158 bool warning_;
00159
00160 bool mode_specific_;
00161 bool remote_;
00162 bool target_reached_;
00163 bool internal_limit_;
00164 bool op_specific_;
00165 bool op_specific1_;
00166 bool man_specific1_;
00167 bool man_specific2_;
00168
00169 double temperature_;
00170
00171 public:
00172
00173 Device() {};
00174
00175 Device(uint16_t CANid):
00176 CANid_(CANid),
00177 desiredVel_(0),
00178 actualVel_(0),
00179 desiredPos_(0),
00180 actualPos_(0),
00181 initialized_(false),
00182 NMTState_("START_UP"),
00183 motorState_("START_UP"),
00184 nmt_init_(false) {};
00185
00186 Device(uint16_t CANid, std::string name, std::string group, std::string bus):
00187 CANid_(CANid),
00188 name_(name),
00189 group_(group),
00190 deviceFile_(bus),
00191 desiredVel_(0),
00192 actualVel_(0),
00193 desiredPos_(0),
00194 actualPos_(0),
00195 initialized_(false),
00196 nmt_init_(false) {};
00197
00198 Device(uint16_t CANid, std::string name, std::string group, std::string bus, double conversion_factor, double offsets):
00199 CANid_(CANid),
00200 name_(name),
00201 group_(group),
00202 deviceFile_(bus),
00203 conversion_factor_(conversion_factor),
00204 offset_(offsets),
00205 desiredVel_(0),
00206 actualVel_(0),
00207 desiredPos_(0),
00208 actualPos_(0),
00209 initialized_(false),
00210 nmt_init_(false) {};
00211
00212 bool getNMTInit(){
00213 return nmt_init_;
00214 }
00215
00216 std::string getNMTState(){
00217 return NMTState_;
00218 }
00219
00220 std::string getMotorState(){
00221 return motorState_;
00222 }
00223
00224 std::vector<char> getManufacturerSWVersion(){
00225 return manufacturer_sw_version_;
00226 }
00227
00228 std::vector<char> getManufacturerHWVersion(){
00229 return manufacturer_hw_version_;
00230 }
00231
00232 std::vector<char> getManufacturerDevName(){
00233 return manufacturer_device_name_;
00234 }
00235
00236 std::string getManufactureErrorRegister(){
00237 return manufacturer_error_register_;
00238 }
00239
00240 std::vector<uint16_t> getVendorID(){
00241 return vendor_id_;
00242 }
00243
00244 std::vector<uint16_t> getProdCode(){
00245 return product_code_;
00246 }
00247
00248 uint16_t getRevNumber(){
00249 return revision_number_;
00250 }
00251
00252 uint8_t getCANid(){
00253 return CANid_;
00254 }
00255
00256 double getConversionFactor(){
00257 return conversion_factor_;
00258 }
00259
00260 std::string getDeviceFile(){
00261 return deviceFile_;
00262 }
00263 std::string getGroup(){
00264 return group_;
00265 }
00266 std::string getName(){
00267 return name_;
00268 }
00269
00270 bool getInitialized(){
00271 return initialized_;
00272 }
00273
00274
00275 bool getVoltageEnabled(){
00276 return volt_enable_;
00277 }
00278
00279 double getDriverTemperature(){
00280 return temperature_;
00281 }
00282
00283 bool getReadySwitchOn(){
00284 return ready_switch_on_;
00285 }
00286
00287 bool getSwitchOn(){
00288 return switched_on_;
00289 }
00290
00291 bool getOpEnabled(){
00292 return op_enable_;
00293 }
00294
00295 bool getQuickStop(){
00296 return quick_stop_;
00297 }
00298
00299 bool getSwitchOnDisabled(){
00300 return switch_on_disabled_;
00301 }
00302
00303 bool getWarning(){
00304 return warning_;
00305 }
00306
00307 bool getModeSpecific(){
00308 return mode_specific_;
00309 }
00310
00311 bool getRemote(){
00312 return remote_;
00313 }
00314 bool getTargetReached(){
00315 return target_reached_;
00316 }
00317
00318 bool getInternalLimits(){
00319 return internal_limit_;
00320 }
00321
00322
00323 bool getOpSpec0(){
00324 return op_specific_;
00325 }
00326
00327 bool getOpSpec1(){
00328 return op_specific1_;
00329 }
00330
00331 bool getManSpec1(){
00332 return man_specific1_;
00333 }
00334
00335 bool getmanSpec2(){
00336 return man_specific2_;
00337 }
00338
00339 bool getHomingError(){
00340 return homingError_;
00341 }
00342
00343
00344 bool getNegativeLimit(){
00345 return hardware_limit_negative_;
00346 }
00347
00348 bool getPositiveLimit(){
00349 return hardware_limit_positive_;
00350 }
00351
00352 bool getFault(){
00353 return fault_;
00354 }
00355
00356
00357 int8_t getCurrentModeofOperation()
00358 {
00359 return modes_of_operation_display_;
00360 }
00361
00362 std::string getErrorRegister(){
00363 return error_register_;
00364 }
00365
00366 bool getIPMode(){
00367 return ip_mode_active_;
00368 }
00369
00370 bool getDriveReferenced(){
00371 return driveReferenced_;
00372 }
00373 double getActualPos(){
00374 return actualPos_;
00375 }
00376 double getDesiredPos(){
00377 return desiredPos_;
00378 }
00379
00380 double getActualVel(){
00381 return actualVel_;
00382 }
00383
00384 double getDesiredVel(){
00385 return desiredVel_;
00386 }
00387
00388 inline std::chrono::milliseconds getTimeStamp_msec(){
00389 return timeStamp_msec_;
00390 }
00391
00392 inline std::chrono::microseconds getTimeStamp_usec(){
00393 return timeStamp_usec_;
00394 }
00395
00396 void setActualPos(double pos){
00397 actualPos_ = pos;
00398 }
00399
00400 void setConversionFactor(double conversion_factor){
00401 conversion_factor_ = conversion_factor;
00402 }
00403
00404 void setDesiredPos(double pos){
00405 desiredPos_ = pos;
00406 }
00407
00408
00409 void setActualVel(double vel){
00410 actualVel_ = vel;
00411 }
00412
00413 void setDesiredVel(double vel){
00414 desiredVel_ = vel;
00415 }
00416
00417 void setMotorState(std::string nextState){
00418 motorState_ = nextState;
00419 }
00420
00421 void setManufacturerSWVersion(std::vector<char> ms_version){
00422 manufacturer_sw_version_ = ms_version;
00423 }
00424
00425 void setManufacturerHWVersion(std::vector<char> mh_version){
00426 manufacturer_hw_version_ = mh_version;
00427 }
00428
00429 void setManufacturerDevName(std::vector<char> dev_name){
00430 manufacturer_device_name_ = dev_name;
00431 }
00432
00433 void setVendorID(std::vector<uint16_t> v_id){
00434 vendor_id_ = v_id;
00435 }
00436
00437 void setProdCode(std::vector<uint16_t> prod_code){
00438 product_code_ = prod_code;
00439 }
00440
00441
00442 void setRevNum(uint16_t rev_num){
00443 revision_number_ = rev_num;
00444 }
00445
00446
00447 void setNMTState(std::string nextState){
00448 NMTState_ = nextState;
00449 }
00450
00451
00452 void setVoltageEnabled(bool voltage_enabled){
00453 volt_enable_ = voltage_enabled;
00454 }
00455
00456 void setDriverTemperature(double temperature){
00457 temperature_ = temperature;
00458 }
00459
00460 void setReadySwitchON(bool r_switch_on){
00461 ready_switch_on_ = r_switch_on;
00462 }
00463
00464 void setSwitchON(bool switch_on){
00465 switched_on_ = switch_on;
00466 }
00467
00468 void setOpEnable(bool op_enable){
00469 op_enable_ = op_enable;
00470 }
00471
00472 void setQuickStop(bool quick_stop){
00473 quick_stop_ = quick_stop;
00474 }
00475
00476 void setSwitchOnDisable(bool switch_disabled){
00477 switch_on_disabled_ = switch_disabled;
00478 }
00479
00480 void setWarning(bool warning){
00481 warning_ = warning;
00482 }
00483
00484
00485 void setModeSpec(bool modespec){
00486 mode_specific_ = modespec;
00487 }
00488
00489
00490 void setRemote(bool remote){
00491 remote_ = remote;
00492 }
00493
00494 void setManSpec1(bool manspec1){
00495 man_specific1_ = manspec1;
00496 }
00497
00498 void setTargetReached(bool target_reached){
00499 target_reached_ = target_reached;
00500 }
00501
00502 void setInternalLimits(bool internal_limits){
00503 internal_limit_ = internal_limits;
00504 }
00505
00506
00507 void setManSpec2(bool manspec2){
00508 man_specific2_ = manspec2;
00509 }
00510
00511 void setOpSpec1(bool opspec1){
00512 op_specific1_ = opspec1;
00513 }
00514
00515 void setOpSpec0(bool opspec0){
00516 op_specific_ = opspec0;
00517 }
00518
00519 void setPositiveLimit(bool pos_limit){
00520 hardware_limit_positive_ = pos_limit;
00521 }
00522
00523
00524 void setNegativeLimit(bool neg_limit){
00525 hardware_limit_negative_ = neg_limit;
00526 }
00527
00528 void setNMTInit(bool nmt_limit)
00529 {
00530 nmt_init_ = nmt_limit;
00531 }
00532
00533 void setFault(bool fault){
00534 fault_ = fault;
00535 }
00536
00537 void setCurrentModeofOperation(int8_t mode_display)
00538 {
00539 modes_of_operation_display_ = mode_display;
00540 }
00541
00542 void setErrorRegister(std::string error_register){
00543 error_register_ = error_register;
00544 }
00545
00546 void setManufacturerErrorRegister(std::string manufacturer_error_register){
00547 manufacturer_error_register_ = manufacturer_error_register;
00548 }
00549
00550 void setIPMode(bool ip_mode){
00551 ip_mode_active_ = ip_mode;
00552 }
00553
00554 void setHoming(bool homing_error){
00555 homingError_ = homing_error;
00556 }
00557
00558 void setInitialized(bool initialized){
00559 initialized_ = initialized;
00560 }
00561
00562 void updateDesiredPos(){
00563 desiredPos_ += desiredVel_ * (syncInterval.count() / 1000.0);
00564 }
00565
00566 void setTimeStamp_msec(std::chrono::milliseconds timeStamp){
00567 timeStamp_msec_ = timeStamp;
00568 }
00569
00570 void setTimeStamp_usec(std::chrono::microseconds timeStamp){
00571 timeStamp_usec_ = timeStamp;
00572 }
00573 };
00574
00575 extern std::map<uint8_t, Device> devices;
00576
00577 class DeviceGroup{
00578
00579 private:
00580
00581 std::vector<uint8_t> CANids_;
00582 std::vector<std::string> names_;
00583 bool initialized_;
00584
00585 public:
00586
00587 DeviceGroup() {};
00588
00589 DeviceGroup(std::vector<uint8_t> CANids):
00590 CANids_(CANids) {};
00591
00592 DeviceGroup(std::vector<uint8_t> CANids, std::vector<std::string> names):
00593 CANids_(CANids),
00594 names_(names),
00595 initialized_(false) {};
00596
00597
00598 std::vector<uint8_t> getCANids(){
00599 return CANids_;
00600 }
00601
00602 std::vector<std::string> getNames(){
00603 return names_;
00604 }
00605
00606 void setInitialized(bool initialized){
00607 initialized_ = initialized;
00608 }
00609
00610 bool getInitialized(){
00611 return initialized_;
00612 }
00613
00614
00615 std::vector<double> getActualPos() {
00616 std::vector<double> actualPos;
00617 for (uint8_t CANid : CANids_)
00618 actualPos.push_back(devices[CANid].getActualPos());
00619 return actualPos;
00620 }
00621
00622 std::vector<double> getDesiredPos() {
00623 std::vector<double> desiredPos;
00624 for (auto CANid : CANids_)
00625 desiredPos.push_back(devices[CANid].getDesiredPos());
00626 return desiredPos;
00627 }
00628
00629 std::vector<double> getActualVel() {
00630 std::vector<double> actualVel;
00631 for (auto CANid : CANids_)
00632 actualVel.push_back(devices[CANid].getActualVel());
00633 return actualVel;
00634 }
00635
00636 std::vector<double> getDesiredVel() {
00637 std::vector<double> desiredVel;
00638 for (auto CANid : CANids_)
00639 desiredVel.push_back(devices[CANid].getDesiredVel());
00640 return desiredVel;
00641 }
00642
00643 void setVel(std::vector<double> velocities) {
00644 for (unsigned int i=0; i<velocities.size(); i++) {
00645 devices[CANids_[i]].setDesiredVel(velocities[i]);
00646 }
00647 }
00648 };
00649
00650 struct SDOkey{
00651 uint16_t index;
00652 uint8_t subindex;
00653
00654 inline SDOkey(TPCANRdMsg m):
00655 index((m.Msg.DATA[2] << 8) + m.Msg.DATA[1]),
00656 subindex(m.Msg.DATA[3]) {};
00657
00658 inline SDOkey(uint16_t i, uint8_t s):
00659 index(i),
00660 subindex(s) {};
00661 };
00662
00663
00664
00665
00666
00667 inline bool operator<(const SDOkey &a, const SDOkey&b) {
00668 return a.index < b.index || (a.index == b.index && a.subindex < b.subindex);
00669 }
00670
00671 inline int32_t rad2mdeg(double phi){
00672 return static_cast<int32_t>(round(phi/(2*M_PI)*360000.0));
00673 }
00674
00675 inline double mdeg2rad(int32_t alpha){
00676 return static_cast<double>(static_cast<double>(alpha)/360000.0*2*M_PI);
00677 }
00678
00679 void sdo_incoming(uint8_t CANid, BYTE data[8]);
00680 void errorword_incoming(uint8_t CANid, BYTE data[8]);
00681 void manufacturer_incoming(uint8_t CANid, BYTE data[8]);
00682
00683 extern std::map<std::string, DeviceGroup> deviceGroups;
00684 extern HANDLE h;
00685 extern std::map<SDOkey, std::function<void (uint8_t CANid, BYTE data[8])> > incomingDataHandlers;
00686 extern std::map<uint16_t, std::function<void (const TPCANRdMsg m)> > incomingPDOHandlers;
00687 extern std::map<uint16_t, std::function<void (const TPCANRdMsg m)> > incomingEMCYHandlers;
00688
00689
00690
00691
00692
00693 void setNMTState(uint16_t CANid, std::string targetState);
00694 void setMotorState(uint16_t CANid, std::string targetState);
00695
00696
00697
00698
00699 void makeRPDOMapping(int object, std::vector<std::string> registers, std::vector<int> sizes, u_int8_t sync_type);
00700 void disableRPDO(int object);
00701 void clearRPDOMapping(int object);
00702 void enableRPDO(int object);
00703
00704 void setObjects();
00705
00706 void makeTPDOMapping(int object, std::vector<std::string> registers, std::vector<int> sizes, u_int8_t sync_type);
00707 void disableTPDO(int object);
00708 void clearTPDOMapping(int object);
00709 void enableTPDO(int object);
00710
00711 void pdoChanged();
00712
00713 void getErrors(uint16_t CANid);
00714 std::vector<char> obtainManSWVersion(uint16_t CANid, std::shared_ptr<TPCANRdMsg> m);
00715 std::vector<char> obtainManHWVersion(uint16_t CANid, std::shared_ptr<TPCANRdMsg> m);
00716 std::vector<char> obtainManDevName(uint16_t CANid, int size_name);
00717 std::vector<uint16_t> obtainVendorID(uint16_t CANid);
00718 uint16_t obtainRevNr(uint16_t CANid, std::shared_ptr<TPCANRdMsg> m);
00719 std::vector<uint16_t> obtainProdCode(uint16_t CANid, std::shared_ptr<TPCANRdMsg> m);
00720 void readErrorsRegister(uint16_t CANid, std::shared_ptr<TPCANRdMsg> m);
00721 void readManErrReg(uint16_t CANid);
00722
00723
00724
00725
00726
00727
00728 extern bool sdo_protect;
00729 extern BYTE protect_msg[];
00730
00731 extern bool atFirstInit;
00732 extern bool recover_active;
00733 extern bool no_position;
00734 extern bool halt_active;
00735
00736 extern bool halt_positive;
00737 extern bool halt_negative;
00738
00739 extern bool use_limit_switch;
00740
00741 extern uint8_t operation_mode;
00742 extern std::string operation_mode_param;
00743
00744 bool openConnection(std::string devName, std::string baudrate);
00745 bool init(std::string deviceFile, std::chrono::milliseconds syncInterval);
00746 void pre_init();
00747 bool recover(std::string deviceFile, std::chrono::milliseconds syncInterval);
00748 void halt(std::string deviceFile, std::chrono::milliseconds syncInterval);
00749
00750 extern std::function< void (uint16_t CANid, double positionValue) > sendPos;
00751 extern std::function< void (uint16_t CANid, double positionValue, double velocityValue) > sendPosPPMode;
00752 extern std::function< void (uint16_t CANid, double velocityValue) > sendVel;
00753 extern std::function< void (uint16_t CANid) > geterrors;
00754
00755
00756
00757
00758
00759
00760 const uint8_t NMT_START_REMOTE_NODE = 0x01;
00761 const uint8_t NMT_STOP_REMOTE_NODE = 0x02;
00762 const uint8_t NMT_ENTER_PRE_OPERATIONAL = 0x80;
00763 const uint8_t NMT_RESET_NODE = 0x81;
00764 const uint8_t NMT_RESET_COMMUNICATION = 0x82;
00765
00766 extern TPCANMsg NMTmsg;
00767
00768 inline void sendNMT(uint8_t CANid, uint8_t command)
00769 {
00770 TPCANMsg NMTmsg;
00771 std::memset(&NMTmsg, 0, sizeof(NMTmsg));
00772 NMTmsg.ID = 0;
00773 NMTmsg.MSGTYPE = 0x00;
00774 NMTmsg.LEN = 2;
00775
00776
00777 NMTmsg.DATA[0] = command;
00778 NMTmsg.DATA[1] = CANid;
00779 CAN_Write(h, &NMTmsg);
00780 }
00781
00782
00783
00784
00785
00786 extern TPCANMsg syncMsg;
00787
00788 inline void sendSync() {
00789 TPCANMsg syncMsg;
00790 std::memset(&syncMsg, 0, sizeof(syncMsg));
00791 syncMsg.ID = 0x80;
00792 syncMsg.MSGTYPE = 0x00;
00793
00794 syncMsg.LEN = 0x00;
00795
00796 CAN_Write(h, &syncMsg);
00797 }
00798
00799
00800
00801
00802
00803 const SDOkey HEARTBEAT(0x1017,0x0);
00804
00805 const uint16_t HEARTBEAT_TIME = 1500;
00806
00807
00808
00809
00810
00811 static unsigned char const EMC_k_1001_GENERIC = 0x01;
00812 static unsigned char const EMC_k_1001_CURRENT = 0x02;
00813 static unsigned char const EMC_k_1001_VOLTAGE = 0x04;
00814 static unsigned char const EMC_k_1001_TEMPERATURE = 0x08;
00815 static unsigned char const EMC_k_1001_COMMUNICATION = 0x10;
00816 static unsigned char const EMC_k_1001_DEV_PROF_SPEC = 0x20;
00817 static unsigned char const EMC_k_1001_RESERVED = 0x40;
00818 static unsigned char const EMC_k_1001_MANUFACTURER = 0x80;
00819
00820
00821
00822
00823
00824 const std::string MS_NOT_READY_TO_SWITCH_ON = "NOT_READY_TO_SWITCH_ON";
00825 const std::string MS_FAULT = "FAULT";
00826 const std::string MS_SWITCHED_ON_DISABLED = "SWITCHED_ON_DISABLED";
00827 const std::string MS_READY_TO_SWITCH_ON = "READY_TO_SWITCH_ON";
00828 const std::string MS_SWITCHED_ON = "SWITCHED_ON";
00829 const std::string MS_OPERATION_ENABLED = "OPERATION_ENABLED";
00830 const std::string MS_QUICK_STOP_ACTIVE = "QUICK_STOP_ACTIVE";
00831 const std::string MS_FAULT_REACTION_ACTIVE = "FAULT_REACTION_ACTIVE";
00832
00833
00834
00835
00836
00837 const SDOkey STATUSWORD(0x6041, 0x0);
00838 const SDOkey ERRORWORD(0x1001, 0x0);
00839 const SDOkey DRIVERTEMPERATURE(0x22A2, 0x0);
00840 const SDOkey MANUFACTURER(0x1002, 0x0);
00841 const SDOkey MANUFACTURERDEVICENAME(0x1008, 0x0);
00842 const SDOkey MANUFACTURERHWVERSION(0x1009, 0x0);
00843 const SDOkey MANUFACTURERSOFTWAREVERSION(0x100A, 0x0);
00844
00845 const SDOkey IDENTITYVENDORID(0x1018, 0x01);
00846 const SDOkey IDENTITYPRODUCTCODE(0x1018, 0x02);
00847 const SDOkey IDENTITYREVNUMBER(0x1018, 0x03);
00848
00849
00850
00851
00852 const SDOkey SCHUNKLINE(0x200b, 0x1);
00853 const SDOkey SCHUNKDETAIL(0x200b, 0x3);
00854
00855
00856
00857 const SDOkey CONTROLWORD(0x6040, 0x0);
00858 const SDOkey MODES_OF_OPERATION(0x6060, 0x0);
00859 const SDOkey MODES_OF_OPERATION_DISPLAY(0x6061, 0x0);
00860 const SDOkey SYNC_TIMEOUT_FACTOR(0x200e, 0x0);
00861 const SDOkey IP_TIME_UNITS(0x60C2, 0x1);
00862 const SDOkey IP_TIME_INDEX(0x60C2, 0x2);
00863 const SDOkey ERROR_CODE(0x603F, 0x0);
00864 const SDOkey ABORT_CONNECTION(0x6007, 0x0);
00865 const SDOkey QUICK_STOP(0x605A, 0x0);
00866 const SDOkey SHUTDOWN(0x605B, 0x0);
00867 const SDOkey DISABLE_CODE(0x605C, 0x0);
00868 const SDOkey HALT(0x605D, 0x0);
00869 const SDOkey FAULT(0x605E, 0x0);
00870 const SDOkey MODES(0x6060, 0x0);
00871
00872
00873 const int TPDO1_msg = 0x180;
00874 const int TPDO2_msg = 0x280;
00875 const int TPDO3_msg = 0x380;
00876 const int TPDO4_msg = 0x480;
00877
00878 const int RPDO1_msg = 0x200;
00879 const int RPDO2_msg = 0x300;
00880 const int RPDO3_msg = 0x400;
00881 const int RPDO4_msg = 0x500;
00882
00883 const int TSDO = 0x580;
00884 const int RSDO = 0x600;
00885
00886
00887 const SDOkey TPDO(0x1800, 0x0);
00888
00889
00890 const SDOkey RPDO(0x1400, 0x0);
00891
00892
00893 const SDOkey TPDO_map(0x1A00, 0x0);
00894
00895
00896 const SDOkey RPDO_map(0x1600, 0x0);
00897
00898 const uint16_t CONTROLWORD_SHUTDOWN = 6;
00899 const uint16_t CONTROLWORD_QUICKSTOP = 2;
00900 const uint16_t CONTROLWORD_SWITCH_ON = 7;
00901 const uint16_t CONTROLWORD_ENABLE_OPERATION = 15;
00902 const uint16_t CONTROLWORD_ENABLE_MOVEMENT = 31;
00903 const uint16_t CONTROLWORD_START_HOMING = 16;
00904 const uint16_t CONTROLWORD_ENABLE_IP_MODE = 16;
00905 const uint16_t CONTROLWORD_DISABLE_INTERPOLATED = 7;
00906 const uint16_t CONTROLWORD_DISABLE_OPERATION = 7;
00907 const uint16_t CONTROL_WORD_DISABLE_VOLTAGE = 0x7D;
00908 const uint16_t CONTROLWORD_FAULT_RESET_0 = 0x00;
00909 const uint16_t CONTROLWORD_FAULT_RESET_1 = 0x80;
00910 const uint16_t CONTROLWORD_HALT = 0x100;
00911
00912 const uint8_t MODES_OF_OPERATION_HOMING_MODE = 0x6;
00913 const uint8_t MODES_OF_OPERATION_PROFILE_POSITION_MODE = 0x1;
00914 const uint8_t MODES_OF_OPERATION_VELOCITY_MODE = 0x2;
00915 const uint8_t MODES_OF_OPERATION_PROFILE_VELOCITY_MODE = 0x3;
00916 const uint8_t MODES_OF_OPERATION_TORQUE_PROFILE_MODE = 0x4;
00917 const uint8_t MODES_OF_OPERATION_INTERPOLATED_POSITION_MODE = 0x7;
00918
00919 static const char * const modesDisplay[] =
00920 {"NO_MODE", "PROFILE_POSITION_MODE", "VELOCITY", "PROFILE_VELOCITY_MODE",
00921 "TORQUE_PROFILED_MODE", "RESERVED", "HOMING_MODE", "INTERPOLATED_POSITION_MODE",
00922 "CYCLIC_SYNCHRONOUS_POSITION"};
00923
00924 const int8_t IP_TIME_INDEX_MILLISECONDS = 0xFD;
00925 const int8_t IP_TIME_INDEX_HUNDREDMICROSECONDS = 0xFC;
00926 const uint8_t SYNC_TIMEOUT_FACTOR_DISABLE_TIMEOUT = 0;
00927
00928 void uploadSDO(uint8_t CANid, SDOkey sdo);
00929 void controlPDO(uint8_t CANid, u_int16_t control1, u_int16_t control2);
00930 void processSingleSDO(uint8_t CANid, std::shared_ptr<TPCANRdMsg> message);
00931 void requestDataBlock1(uint8_t CANid);
00932 void requestDataBlock2(uint8_t CANid);
00933
00934 void sendSDO(uint8_t CANid, SDOkey sdo, uint32_t value);
00935 void sendSDO(uint8_t CANid, SDOkey sdo, int32_t value);
00936 void sendSDO_unknown(uint8_t CANid, SDOkey sdo, int32_t value);
00937 void sendSDO(uint8_t CANid, SDOkey sdo, uint16_t value);
00938 void sendSDO(uint8_t CANid, SDOkey sdo, uint8_t value);
00939
00940
00941
00942
00943
00944 void initDeviceManagerThread(std::function<void ()> const& deviceManager);
00945 void deviceManager();
00946
00947
00948 void defaultPDOOutgoing(uint16_t CANid, double positionValue);
00949 void defaultPDOOutgoing_interpolated(uint16_t CANid, double positionValue);
00950 void defaultPDO_incoming(uint16_t CANid, const TPCANRdMsg m);
00951 void defaultPDO_incoming_status(uint16_t CANid, const TPCANRdMsg m);
00952 void defaultPDO_incoming_pos(uint16_t CANid, const TPCANRdMsg m);
00953 void defaultEMCY_incoming(uint16_t CANid, const TPCANRdMsg m);
00954
00955
00956
00957
00958
00959 void initListenerThread(std::function<void ()> const& listener);
00960 void defaultListener();
00961 }
00962
00963 #endif