Classes | |
class | Device |
class | DeviceGroup |
struct | SDOkey |
Functions | |
const SDOkey | ABORT_CONNECTION (0x6007, 0x0) |
void | clearRPDOMapping (std::string chainName, int object) |
void | clearTPDOMapping (std::string chainName, int object) |
void | controlPDO (uint8_t CANid, u_int16_t control1, u_int16_t control2) |
const SDOkey | CONTROLWORD (0x6040, 0x0) |
void | defaultEMCY_incoming (uint16_t CANid, const TPCANRdMsg m) |
void | defaultListener () |
void | defaultPDO_incoming (uint16_t CANid, const TPCANRdMsg m) |
void | defaultPDO_incoming_pos (uint16_t CANid, const TPCANRdMsg m) |
void | defaultPDO_incoming_status (uint16_t CANid, const TPCANRdMsg m) |
void | defaultPDOOutgoing (uint16_t CANid, double positionValue) |
void | defaultPDOOutgoing_interpolated (uint16_t CANid, double positionValue) |
void | deviceManager (std::string chainName) |
const SDOkey | DISABLE_CODE (0x605C, 0x0) |
void | disableRPDO (std::string chainName, int object) |
void | disableTPDO (std::string chainName, int object) |
const SDOkey | DRIVERTEMPERATURE (0x22A2, 0x0) |
void | enableRPDO (std::string chainName, int object) |
void | enableTPDO (std::string chainName, int object) |
const SDOkey | ERROR_CODE (0x603F, 0x0) |
const SDOkey | ERRORWORD (0x1001, 0x0) |
void | errorword_incoming (uint8_t CANid, BYTE data[8]) |
const SDOkey | FAULT (0x605E, 0x0) |
void | getErrors (uint16_t CANid) |
void | halt (std::string deviceFile, std::string chainName, std::chrono::milliseconds syncInterval) |
const SDOkey | HALT (0x605D, 0x0) |
const SDOkey | HEARTBEAT (0x1017, 0x0) |
const SDOkey | IDENTITYPRODUCTCODE (0x1018, 0x02) |
const SDOkey | IDENTITYREVNUMBER (0x1018, 0x03) |
const SDOkey | IDENTITYVENDORID (0x1018, 0x01) |
bool | init (std::string deviceFile, std::string chainName, std::chrono::milliseconds syncInterval) |
bool | init (std::string deviceFile, std::string chainName, const int8_t mode_of_operation) |
void | initDeviceManagerThread (std::string chainName, std::function< void(std::string)> const &deviceManager) |
void | initListenerThread (std::function< void()> const &listener) |
const SDOkey | IP_TIME_INDEX (0x60C2, 0x2) |
const SDOkey | IP_TIME_UNITS (0x60C2, 0x1) |
void | makeRPDOMapping (std::string chainName, int object, std::vector< std::string > registers, std::vector< int > sizes, u_int8_t sync_type) |
void | makeTPDOMapping (std::string chainName, int object, std::vector< std::string > registers, std::vector< int > sizes, u_int8_t sync_type) |
const SDOkey | MANUFACTURER (0x1002, 0x0) |
void | manufacturer_incoming (uint8_t CANid, BYTE data[8]) |
const SDOkey | MANUFACTURERDEVICENAME (0x1008, 0x0) |
const SDOkey | MANUFACTURERHWVERSION (0x1009, 0x0) |
const SDOkey | MANUFACTURERSOFTWAREVERSION (0x100A, 0x0) |
double | mdeg2rad (int32_t alpha) |
const SDOkey | MODES (0x6060, 0x0) |
const SDOkey | MODES_OF_OPERATION (0x6060, 0x0) |
const SDOkey | MODES_OF_OPERATION_DISPLAY (0x6061, 0x0) |
std::vector< char > | obtainManDevName (uint16_t CANid, int size_name) |
std::vector< char > | obtainManHWVersion (uint16_t CANid, std::shared_ptr< TPCANRdMsg > m) |
std::vector< char > | obtainManSWVersion (uint16_t CANid, std::shared_ptr< TPCANRdMsg > m) |
std::vector< uint16_t > | obtainProdCode (uint16_t CANid, std::shared_ptr< TPCANRdMsg > m) |
uint16_t | obtainRevNr (uint16_t CANid, std::shared_ptr< TPCANRdMsg > m) |
std::vector< uint16_t > | obtainVendorID (uint16_t CANid) |
bool | openConnection (std::string devName, std::string baudrate) |
bool | operator< (const SDOkey &a, const SDOkey &b) |
void | pdoChanged (std::string chainName) |
void | pre_init (std::string chainName) |
void | processSingleSDO (uint8_t CANid, std::shared_ptr< TPCANRdMsg > message) |
const SDOkey | QUICK_STOP (0x605A, 0x0) |
int32_t | rad2mdeg (double phi) |
void | readErrorsRegister (uint16_t CANid, std::shared_ptr< TPCANRdMsg > m) |
void | readManErrReg (uint16_t CANid) |
bool | recover (std::string deviceFile, std::string chainName, std::chrono::milliseconds syncInterval) |
void | requestDataBlock1 (uint8_t CANid) |
void | requestDataBlock2 (uint8_t CANid) |
const SDOkey | RPDO (0x1400, 0x0) |
const SDOkey | RPDO_map (0x1600, 0x0) |
const SDOkey | SCHUNKDETAIL (0x200b, 0x3) |
const SDOkey | SCHUNKLINE (0x200b, 0x1) |
void | sdo_incoming (uint8_t CANid, BYTE data[8]) |
void | sendNMT (uint8_t CANid, uint8_t command) |
void | sendSDO (uint8_t CANid, SDOkey sdo, uint32_t value) |
void | sendSDO (uint8_t CANid, SDOkey sdo, int32_t value) |
void | sendSDO (uint8_t CANid, SDOkey sdo, uint16_t value) |
void | sendSDO (uint8_t CANid, SDOkey sdo, uint8_t value) |
void | sendSDO_unknown (uint8_t CANid, SDOkey sdo, int32_t value) |
void | sendSync () |
void | setMotorState (uint16_t CANid, std::string targetState) |
void | setNMTState (uint16_t CANid, std::string targetState) |
void | setObjects (std::string chainName) |
bool | setOperationMode (uint16_t CANid, const int8_t targetMode, double timeout=3.0) |
const SDOkey | SHUTDOWN (0x605B, 0x0) |
const SDOkey | STATUSWORD (0x6041, 0x0) |
const SDOkey | SYNC_TIMEOUT_FACTOR (0x200e, 0x0) |
const SDOkey | TPDO (0x1800, 0x0) |
const SDOkey | TPDO_map (0x1A00, 0x0) |
void | uploadSDO (uint8_t CANid, SDOkey sdo) |
Variables | |
bool | atFirstInit = true |
std::string | baudRate |
static std::map< std::string, uint32_t > | baudrates |
const uint16_t | CONTROL_WORD_DISABLE_VOLTAGE = 0x7D |
const uint16_t | CONTROLWORD_DISABLE_INTERPOLATED = 7 |
const uint16_t | CONTROLWORD_DISABLE_OPERATION = 7 |
const uint16_t | CONTROLWORD_ENABLE_IP_MODE = 16 |
const uint16_t | CONTROLWORD_ENABLE_MOVEMENT = 31 |
const uint16_t | CONTROLWORD_ENABLE_OPERATION = 15 |
const uint16_t | CONTROLWORD_FAULT_RESET_0 = 0x00 |
const uint16_t | CONTROLWORD_FAULT_RESET_1 = 0x80 |
const uint16_t | CONTROLWORD_HALT = 0x100 |
const uint16_t | CONTROLWORD_QUICKSTOP = 2 |
const uint16_t | CONTROLWORD_SHUTDOWN = 6 |
const uint16_t | CONTROLWORD_START_HOMING = 16 |
const uint16_t | CONTROLWORD_SWITCH_ON = 7 |
std::map< std::string, DeviceGroup > | deviceGroups |
std::map< uint8_t, Device > | devices |
std::chrono::duration< double > | elapsed_seconds |
static unsigned char const | EMC_k_1001_COMMUNICATION = 0x10 |
static unsigned char const | EMC_k_1001_CURRENT = 0x02 |
static unsigned char const | EMC_k_1001_DEV_PROF_SPEC = 0x20 |
static unsigned char const | EMC_k_1001_GENERIC = 0x01 |
static unsigned char const | EMC_k_1001_MANUFACTURER = 0x80 |
static unsigned char const | EMC_k_1001_RESERVED = 0x40 |
static unsigned char const | EMC_k_1001_TEMPERATURE = 0x08 |
static unsigned char const | EMC_k_1001_VOLTAGE = 0x04 |
std::chrono::time_point < std::chrono::high_resolution_clock > | end |
std::function< void(uint16_t CANid) > | geterrors |
HANDLE | h |
bool | halt_active |
bool | halt_negative |
bool | halt_positive |
const uint16_t | HEARTBEAT_TIME = 1500 |
std::map< SDOkey, std::function< void(uint8_t CANid, BYTE data[8])> > | incomingDataHandlers |
std::map< uint16_t, std::function< void(const TPCANRdMsg m)> > | incomingEMCYHandlers |
std::map< uint16_t, std::function< void(const TPCANRdMsg m)> > | incomingPDOHandlers |
int | initTrials = 0 |
const int8_t | IP_TIME_INDEX_HUNDREDMICROSECONDS = 0xFC |
const int8_t | IP_TIME_INDEX_MILLISECONDS = 0xFD |
std::vector< std::thread > | managerThreads |
const int8_t | MODES_OF_OPERATION_HOMING_MODE = 0x6 |
const int8_t | MODES_OF_OPERATION_INTERPOLATED_POSITION_MODE = 0x7 |
const int8_t | MODES_OF_OPERATION_PROFILE_POSITION_MODE = 0x1 |
const int8_t | MODES_OF_OPERATION_PROFILE_VELOCITY_MODE = 0x3 |
const int8_t | MODES_OF_OPERATION_TORQUE_PROFILE_MODE = 0x4 |
const int8_t | MODES_OF_OPERATION_VELOCITY_MODE = 0x2 |
static const char *const | modesDisplay [] |
const std::string | MS_FAULT = "FAULT" |
const std::string | MS_FAULT_REACTION_ACTIVE = "FAULT_REACTION_ACTIVE" |
const std::string | MS_NOT_READY_TO_SWITCH_ON = "NOT_READY_TO_SWITCH_ON" |
const std::string | MS_OPERATION_ENABLED = "OPERATION_ENABLED" |
const std::string | MS_QUICK_STOP_ACTIVE = "QUICK_STOP_ACTIVE" |
const std::string | MS_READY_TO_SWITCH_ON = "READY_TO_SWITCH_ON" |
const std::string | MS_SWITCHED_ON = "SWITCHED_ON" |
const std::string | MS_SWITCHED_ON_DISABLED = "SWITCHED_ON_DISABLED" |
const uint8_t | NMT_ENTER_PRE_OPERATIONAL = 0x80 |
const uint8_t | NMT_RESET_COMMUNICATION = 0x82 |
const uint8_t | NMT_RESET_NODE = 0x81 |
const uint8_t | NMT_START_REMOTE_NODE = 0x01 |
const uint8_t | NMT_STOP_REMOTE_NODE = 0x02 |
TPCANMsg | NMTmsg |
bool | no_position |
std::vector< std::string > | openDeviceFiles |
std::string | operation_mode_param |
BYTE | protect_msg [] |
bool | recover_active |
const int | RPDO1_msg = 0x200 |
const int | RPDO2_msg = 0x300 |
const int | RPDO3_msg = 0x400 |
const int | RPDO4_msg = 0x500 |
const int | RSDO = 0x600 |
bool | sdo_protect = false |
std::function< void(uint16_t CANid, double positionValue) > | sendPos |
std::function< void(uint16_t CANid, double positionValue, double velocityValue) > | sendPosPPMode |
std::function< void(uint16_t CANid, double velocityValue) > | sendVel |
std::chrono::time_point < std::chrono::high_resolution_clock > | start |
const uint8_t | SYNC_TIMEOUT_FACTOR_DISABLE_TIMEOUT = 0 |
std::chrono::milliseconds | syncInterval |
TPCANMsg | syncMsg |
const int | TPDO1_msg = 0x180 |
const int | TPDO2_msg = 0x280 |
const int | TPDO3_msg = 0x380 |
const int | TPDO4_msg = 0x480 |
const int | TSDO = 0x580 |
bool | use_limit_switch = false |
const SDOkey canopen::ABORT_CONNECTION | ( | 0x6007 | , |
0x0 | |||
) |
void canopen::clearRPDOMapping | ( | std::string | chainName, |
int | object | ||
) |
Definition at line 1766 of file ipa_canopen_core.cpp.
void canopen::clearTPDOMapping | ( | std::string | chainName, |
int | object | ||
) |
void canopen::controlPDO | ( | uint8_t | CANid, |
u_int16_t | control1, | ||
u_int16_t | control2 | ||
) |
Definition at line 707 of file ipa_canopen_core.cpp.
const SDOkey canopen::CONTROLWORD | ( | 0x6040 | , |
0x0 | |||
) |
void canopen::defaultEMCY_incoming | ( | uint16_t | CANid, |
const TPCANRdMsg | m | ||
) |
Definition at line 916 of file ipa_canopen_core.cpp.
void canopen::defaultListener | ( | ) |
Definition at line 1194 of file ipa_canopen_core.cpp.
void canopen::defaultPDO_incoming | ( | uint16_t | CANid, |
const TPCANRdMsg | m | ||
) |
Definition at line 1068 of file ipa_canopen_core.cpp.
void canopen::defaultPDO_incoming_pos | ( | uint16_t | CANid, |
const TPCANRdMsg | m | ||
) |
Definition at line 1039 of file ipa_canopen_core.cpp.
void canopen::defaultPDO_incoming_status | ( | uint16_t | CANid, |
const TPCANRdMsg | m | ||
) |
Definition at line 928 of file ipa_canopen_core.cpp.
void canopen::defaultPDOOutgoing | ( | uint16_t | CANid, |
double | positionValue | ||
) |
Definition at line 893 of file ipa_canopen_core.cpp.
void canopen::defaultPDOOutgoing_interpolated | ( | uint16_t | CANid, |
double | positionValue | ||
) |
Definition at line 877 of file ipa_canopen_core.cpp.
void canopen::deviceManager | ( | std::string | chainName | ) |
Definition at line 836 of file ipa_canopen_core.cpp.
const SDOkey canopen::DISABLE_CODE | ( | 0x605C | , |
0x0 | |||
) |
void canopen::disableRPDO | ( | std::string | chainName, |
int | object | ||
) |
Definition at line 1699 of file ipa_canopen_core.cpp.
void canopen::disableTPDO | ( | std::string | chainName, |
int | object | ||
) |
Definition at line 1862 of file ipa_canopen_core.cpp.
const SDOkey canopen::DRIVERTEMPERATURE | ( | 0x22A2 | , |
0x0 | |||
) |
void canopen::enableRPDO | ( | std::string | chainName, |
int | object | ||
) |
Definition at line 1821 of file ipa_canopen_core.cpp.
void canopen::enableTPDO | ( | std::string | chainName, |
int | object | ||
) |
const SDOkey canopen::ERROR_CODE | ( | 0x603F | , |
0x0 | |||
) |
const SDOkey canopen::ERRORWORD | ( | 0x1001 | , |
0x0 | |||
) |
void canopen::errorword_incoming | ( | uint8_t | CANid, |
BYTE | data[8] | ||
) |
Definition at line 1307 of file ipa_canopen_core.cpp.
const SDOkey canopen::FAULT | ( | 0x605E | , |
0x0 | |||
) |
void canopen::getErrors | ( | uint16_t | CANid | ) |
Definition at line 1284 of file ipa_canopen_core.cpp.
void canopen::halt | ( | std::string | deviceFile, |
std::string | chainName, | ||
std::chrono::milliseconds | syncInterval | ||
) |
7
Definition at line 470 of file ipa_canopen_core.cpp.
const SDOkey canopen::HALT | ( | 0x605D | , |
0x0 | |||
) |
const SDOkey canopen::HEARTBEAT | ( | 0x1017 | , |
0x0 | |||
) |
const SDOkey canopen::IDENTITYPRODUCTCODE | ( | 0x1018 | , |
0x02 | |||
) |
const SDOkey canopen::IDENTITYREVNUMBER | ( | 0x1018 | , |
0x03 | |||
) |
const SDOkey canopen::IDENTITYVENDORID | ( | 0x1018 | , |
0x01 | |||
) |
bool canopen::init | ( | std::string | deviceFile, |
std::string | chainName, | ||
std::chrono::milliseconds | syncInterval | ||
) |
Definition at line 363 of file ipa_canopen_core.cpp.
bool canopen::init | ( | std::string | deviceFile, |
std::string | chainName, | ||
const int8_t | mode_of_operation | ||
) |
Definition at line 142 of file ipa_canopen_core.cpp.
void canopen::initDeviceManagerThread | ( | std::string | chainName, |
std::function< void(std::string)> const & | deviceManager | ||
) |
Definition at line 828 of file ipa_canopen_core.cpp.
void canopen::initListenerThread | ( | std::function< void()> const & | listener | ) |
Definition at line 1186 of file ipa_canopen_core.cpp.
const SDOkey canopen::IP_TIME_INDEX | ( | 0x60C2 | , |
0x2 | |||
) |
const SDOkey canopen::IP_TIME_UNITS | ( | 0x60C2 | , |
0x1 | |||
) |
void canopen::makeRPDOMapping | ( | std::string | chainName, |
int | object, | ||
std::vector< std::string > | registers, | ||
std::vector< int > | sizes, | ||
u_int8_t | sync_type | ||
) |
void canopen::makeTPDOMapping | ( | std::string | chainName, |
int | object, | ||
std::vector< std::string > | registers, | ||
std::vector< int > | sizes, | ||
u_int8_t | sync_type | ||
) |
const SDOkey canopen::MANUFACTURER | ( | 0x1002 | , |
0x0 | |||
) |
void canopen::manufacturer_incoming | ( | uint8_t | CANid, |
BYTE | data[8] | ||
) |
Definition at line 1289 of file ipa_canopen_core.cpp.
const SDOkey canopen::MANUFACTURERDEVICENAME | ( | 0x1008 | , |
0x0 | |||
) |
const SDOkey canopen::MANUFACTURERHWVERSION | ( | 0x1009 | , |
0x0 | |||
) |
const SDOkey canopen::MANUFACTURERSOFTWAREVERSION | ( | 0x100A | , |
0x0 | |||
) |
double canopen::mdeg2rad | ( | int32_t | alpha | ) | [inline] |
const SDOkey canopen::MODES | ( | 0x6060 | , |
0x0 | |||
) |
const SDOkey canopen::MODES_OF_OPERATION | ( | 0x6060 | , |
0x0 | |||
) |
const SDOkey canopen::MODES_OF_OPERATION_DISPLAY | ( | 0x6061 | , |
0x0 | |||
) |
std::vector< char > canopen::obtainManDevName | ( | uint16_t | CANid, |
int | size_name | ||
) |
Definition at line 1440 of file ipa_canopen_core.cpp.
std::vector< char > canopen::obtainManHWVersion | ( | uint16_t | CANid, |
std::shared_ptr< TPCANRdMsg > | m | ||
) |
Definition at line 1460 of file ipa_canopen_core.cpp.
std::vector< char > canopen::obtainManSWVersion | ( | uint16_t | CANid, |
std::shared_ptr< TPCANRdMsg > | m | ||
) |
Definition at line 1499 of file ipa_canopen_core.cpp.
std::vector< uint16_t > canopen::obtainProdCode | ( | uint16_t | CANid, |
std::shared_ptr< TPCANRdMsg > | m | ||
) |
Definition at line 1403 of file ipa_canopen_core.cpp.
uint16_t canopen::obtainRevNr | ( | uint16_t | CANid, |
std::shared_ptr< TPCANRdMsg > | m | ||
) |
Definition at line 1426 of file ipa_canopen_core.cpp.
std::vector< uint16_t > canopen::obtainVendorID | ( | uint16_t | CANid | ) |
Definition at line 1397 of file ipa_canopen_core.cpp.
bool canopen::openConnection | ( | std::string | devName, |
std::string | baudrate | ||
) |
Definition at line 109 of file ipa_canopen_core.cpp.
bool canopen::operator< | ( | const SDOkey & | a, |
const SDOkey & | b | ||
) | [inline] |
void canopen::pdoChanged | ( | std::string | chainName | ) |
Definition at line 1676 of file ipa_canopen_core.cpp.
void canopen::pre_init | ( | std::string | chainName | ) |
Definition at line 120 of file ipa_canopen_core.cpp.
void canopen::processSingleSDO | ( | uint8_t | CANid, |
std::shared_ptr< TPCANRdMsg > | message | ||
) |
Definition at line 1665 of file ipa_canopen_core.cpp.
const SDOkey canopen::QUICK_STOP | ( | 0x605A | , |
0x0 | |||
) |
int32_t canopen::rad2mdeg | ( | double | phi | ) | [inline] |
void canopen::readErrorsRegister | ( | uint16_t | CANid, |
std::shared_ptr< TPCANRdMsg > | m | ||
) |
Definition at line 1363 of file ipa_canopen_core.cpp.
void canopen::readManErrReg | ( | uint16_t | CANid | ) |
Definition at line 1358 of file ipa_canopen_core.cpp.
bool canopen::recover | ( | std::string | deviceFile, |
std::string | chainName, | ||
std::chrono::milliseconds | syncInterval | ||
) |
Definition at line 380 of file ipa_canopen_core.cpp.
void canopen::requestDataBlock1 | ( | uint8_t | CANid | ) |
Definition at line 671 of file ipa_canopen_core.cpp.
void canopen::requestDataBlock2 | ( | uint8_t | CANid | ) |
Definition at line 689 of file ipa_canopen_core.cpp.
const SDOkey canopen::RPDO | ( | 0x1400 | , |
0x0 | |||
) |
const SDOkey canopen::RPDO_map | ( | 0x1600 | , |
0x0 | |||
) |
const SDOkey canopen::SCHUNKDETAIL | ( | 0x200b | , |
0x3 | |||
) |
const SDOkey canopen::SCHUNKLINE | ( | 0x200b | , |
0x1 | |||
) |
void canopen::sdo_incoming | ( | uint8_t | CANid, |
BYTE | data[8] | ||
) |
Definition at line 1565 of file ipa_canopen_core.cpp.
void canopen::sendNMT | ( | uint8_t | CANid, |
uint8_t | command | ||
) | [inline] |
void canopen::sendSDO | ( | uint8_t | CANid, |
SDOkey | sdo, | ||
uint32_t | value | ||
) |
Definition at line 737 of file ipa_canopen_core.cpp.
void canopen::sendSDO | ( | uint8_t | CANid, |
SDOkey | sdo, | ||
int32_t | value | ||
) |
Definition at line 754 of file ipa_canopen_core.cpp.
void canopen::sendSDO | ( | uint8_t | CANid, |
SDOkey | sdo, | ||
uint16_t | value | ||
) |
Definition at line 807 of file ipa_canopen_core.cpp.
void canopen::sendSDO | ( | uint8_t | CANid, |
SDOkey | sdo, | ||
uint8_t | value | ||
) |
Definition at line 788 of file ipa_canopen_core.cpp.
void canopen::sendSDO_unknown | ( | uint8_t | CANid, |
SDOkey | sdo, | ||
int32_t | value | ||
) |
Definition at line 771 of file ipa_canopen_core.cpp.
void canopen::sendSync | ( | ) | [inline] |
void canopen::setMotorState | ( | uint16_t | CANid, |
std::string | targetState | ||
) |
Definition at line 567 of file ipa_canopen_core.cpp.
void canopen::setNMTState | ( | uint16_t | CANid, |
std::string | targetState | ||
) |
Definition at line 526 of file ipa_canopen_core.cpp.
void canopen::setObjects | ( | std::string | chainName | ) |
Definition at line 1735 of file ipa_canopen_core.cpp.
bool canopen::setOperationMode | ( | uint16_t | CANid, |
const int8_t | targetMode, | ||
double | timeout = 3.0 |
||
) |
Definition at line 531 of file ipa_canopen_core.cpp.
const SDOkey canopen::SHUTDOWN | ( | 0x605B | , |
0x0 | |||
) |
const SDOkey canopen::STATUSWORD | ( | 0x6041 | , |
0x0 | |||
) |
const SDOkey canopen::SYNC_TIMEOUT_FACTOR | ( | 0x200e | , |
0x0 | |||
) |
const SDOkey canopen::TPDO | ( | 0x1800 | , |
0x0 | |||
) |
const SDOkey canopen::TPDO_map | ( | 0x1A00 | , |
0x0 | |||
) |
void canopen::uploadSDO | ( | uint8_t | CANid, |
SDOkey | sdo | ||
) |
Definition at line 719 of file ipa_canopen_core.cpp.
bool canopen::atFirstInit = true |
std::string canopen::baudRate |
Definition at line 77 of file ipa_canopen_core.cpp.
std::map<std::string, uint32_t> canopen::baudrates [static] |
{ {"1M" , CAN_BAUD_1M}, {"500K" , CAN_BAUD_500K}, {"250K" , CAN_BAUD_250K}, {"125K" , CAN_BAUD_125K}, {"100K" , CAN_BAUD_100K}, {"50K" , CAN_BAUD_50K}, {"20K" , CAN_BAUD_20K}, {"10K" , CAN_BAUD_10K}, {"5K" , CAN_BAUD_5K} }
const uint16_t canopen::CONTROL_WORD_DISABLE_VOLTAGE = 0x7D |
const uint16_t canopen::CONTROLWORD_DISABLE_INTERPOLATED = 7 |
const uint16_t canopen::CONTROLWORD_DISABLE_OPERATION = 7 |
const uint16_t canopen::CONTROLWORD_ENABLE_IP_MODE = 16 |
const uint16_t canopen::CONTROLWORD_ENABLE_MOVEMENT = 31 |
const uint16_t canopen::CONTROLWORD_ENABLE_OPERATION = 15 |
const uint16_t canopen::CONTROLWORD_FAULT_RESET_0 = 0x00 |
const uint16_t canopen::CONTROLWORD_FAULT_RESET_1 = 0x80 |
const uint16_t canopen::CONTROLWORD_HALT = 0x100 |
const uint16_t canopen::CONTROLWORD_QUICKSTOP = 2 |
const uint16_t canopen::CONTROLWORD_SHUTDOWN = 6 |
const uint16_t canopen::CONTROLWORD_START_HOMING = 16 |
const uint16_t canopen::CONTROLWORD_SWITCH_ON = 7 |
std::map< std::string, DeviceGroup > canopen::deviceGroups |
Definition at line 79 of file ipa_canopen_core.cpp.
std::map< uint8_t, Device > canopen::devices |
Definition at line 78 of file ipa_canopen_core.cpp.
std::chrono::duration<double> canopen::elapsed_seconds |
Definition at line 102 of file ipa_canopen_core.cpp.
unsigned char const canopen::EMC_k_1001_COMMUNICATION = 0x10 [static] |
unsigned char const canopen::EMC_k_1001_CURRENT = 0x02 [static] |
unsigned char const canopen::EMC_k_1001_DEV_PROF_SPEC = 0x20 [static] |
unsigned char const canopen::EMC_k_1001_GENERIC = 0x01 [static] |
unsigned char const canopen::EMC_k_1001_MANUFACTURER = 0x80 [static] |
unsigned char const canopen::EMC_k_1001_RESERVED = 0x40 [static] |
unsigned char const canopen::EMC_k_1001_TEMPERATURE = 0x08 [static] |
unsigned char const canopen::EMC_k_1001_VOLTAGE = 0x04 [static] |
std::chrono::time_point<std::chrono::high_resolution_clock> canopen::end |
Definition at line 100 of file ipa_canopen_core.cpp.
std::function< void (uint16_t CANid) > canopen::geterrors |
Definition at line 80 of file ipa_canopen_core.cpp.
bool canopen::halt_active |
Definition at line 91 of file ipa_canopen_core.cpp.
Definition at line 94 of file ipa_canopen_core.cpp.
Definition at line 93 of file ipa_canopen_core.cpp.
const uint16_t canopen::HEARTBEAT_TIME = 1500 |
std::map<SDOkey, std::function<void (uint8_t CANid, BYTE data[8])> > canopen::incomingDataHandlers |
std::map< uint16_t, std::function< void(const TPCANRdMsg m)> > canopen::incomingEMCYHandlers |
Definition at line 89 of file ipa_canopen_core.cpp.
std::map< uint16_t, std::function< void(const TPCANRdMsg m)> > canopen::incomingPDOHandlers |
Definition at line 85 of file ipa_canopen_core.cpp.
int canopen::initTrials = 0 |
Definition at line 84 of file ipa_canopen_core.cpp.
const int8_t canopen::IP_TIME_INDEX_HUNDREDMICROSECONDS = 0xFC |
const int8_t canopen::IP_TIME_INDEX_MILLISECONDS = 0xFD |
std::vector< std::thread > canopen::managerThreads |
Definition at line 81 of file ipa_canopen_core.cpp.
const int8_t canopen::MODES_OF_OPERATION_HOMING_MODE = 0x6 |
const int8_t canopen::MODES_OF_OPERATION_INTERPOLATED_POSITION_MODE = 0x7 |
const int8_t canopen::MODES_OF_OPERATION_PROFILE_POSITION_MODE = 0x1 |
const int8_t canopen::MODES_OF_OPERATION_PROFILE_VELOCITY_MODE = 0x3 |
const int8_t canopen::MODES_OF_OPERATION_TORQUE_PROFILE_MODE = 0x4 |
const int8_t canopen::MODES_OF_OPERATION_VELOCITY_MODE = 0x2 |
const char* const canopen::modesDisplay[] [static] |
const std::string canopen::MS_FAULT = "FAULT" |
const std::string canopen::MS_FAULT_REACTION_ACTIVE = "FAULT_REACTION_ACTIVE" |
const std::string canopen::MS_NOT_READY_TO_SWITCH_ON = "NOT_READY_TO_SWITCH_ON" |
const std::string canopen::MS_OPERATION_ENABLED = "OPERATION_ENABLED" |
const std::string canopen::MS_QUICK_STOP_ACTIVE = "QUICK_STOP_ACTIVE" |
const std::string canopen::MS_READY_TO_SWITCH_ON = "READY_TO_SWITCH_ON" |
const std::string canopen::MS_SWITCHED_ON = "SWITCHED_ON" |
const std::string canopen::MS_SWITCHED_ON_DISABLED = "SWITCHED_ON_DISABLED" |
const uint8_t canopen::NMT_ENTER_PRE_OPERATIONAL = 0x80 |
const uint8_t canopen::NMT_RESET_COMMUNICATION = 0x82 |
const uint8_t canopen::NMT_RESET_NODE = 0x81 |
const uint8_t canopen::NMT_START_REMOTE_NODE = 0x01 |
const uint8_t canopen::NMT_STOP_REMOTE_NODE = 0x02 |
Definition at line 659 of file ipa_canopen_core.cpp.
bool canopen::no_position |
std::vector< std::string > canopen::openDeviceFiles |
Definition at line 82 of file ipa_canopen_core.cpp.
std::string canopen::operation_mode_param |
Definition at line 98 of file ipa_canopen_core.cpp.
Definition at line 74 of file ipa_canopen_core.cpp.
Definition at line 90 of file ipa_canopen_core.cpp.
const int canopen::RPDO1_msg = 0x200 |
const int canopen::RPDO2_msg = 0x300 |
const int canopen::RPDO3_msg = 0x400 |
const int canopen::RPDO4_msg = 0x500 |
const int canopen::RSDO = 0x600 |
bool canopen::sdo_protect = false |
Definition at line 73 of file ipa_canopen_core.cpp.
std::function< void(uint16_t CANid, double positionValue) > canopen::sendPos |
Definition at line 874 of file ipa_canopen_core.cpp.
std::function< void(uint16_t CANid, double positionValue, double velocityValue) > canopen::sendPosPPMode |
Definition at line 875 of file ipa_canopen_core.cpp.
std::function< void(uint16_t CANid, double velocityValue) > canopen::sendVel |
Definition at line 873 of file ipa_canopen_core.cpp.
std::chrono::time_point<std::chrono::high_resolution_clock> canopen::start |
Definition at line 100 of file ipa_canopen_core.cpp.
const uint8_t canopen::SYNC_TIMEOUT_FACTOR_DISABLE_TIMEOUT = 0 |
std::chrono::milliseconds canopen::syncInterval |
Definition at line 76 of file ipa_canopen_core.cpp.
Definition at line 665 of file ipa_canopen_core.cpp.
const int canopen::TPDO1_msg = 0x180 |
const int canopen::TPDO2_msg = 0x280 |
const int canopen::TPDO3_msg = 0x380 |
const int canopen::TPDO4_msg = 0x480 |
const int canopen::TSDO = 0x580 |
bool canopen::use_limit_switch = false |
Definition at line 96 of file ipa_canopen_core.cpp.