Implementation of canopen driver. More...
#include <iostream>
#include <map>
#include <vector>
#include <string>
#include <cstring>
#include <chrono>
#include <unordered_map>
#include <functional>
#include <cstdlib>
#include <thread>
#include <math.h>
#include <libpcan.h>
#include <utility>
#include <fcntl.h>
#include <stdint.h>
#include <inttypes.h>
#include "schunkErrors.h"
Go to the source code of this file.
Classes | |
class | canopen::Device |
class | canopen::DeviceGroup |
struct | canopen::SDOkey |
Namespaces | |
namespace | canopen |
Functions | |
const SDOkey | canopen::ABORT_CONNECTION (0x6007, 0x0) |
void | canopen::clearRPDOMapping (int object) |
void | canopen::clearTPDOMapping (int object) |
void | canopen::controlPDO (uint8_t CANid, u_int16_t control1, u_int16_t control2) |
const SDOkey | canopen::CONTROLWORD (0x6040, 0x0) |
void | canopen::defaultEMCY_incoming (uint16_t CANid, const TPCANRdMsg m) |
void | canopen::defaultListener () |
void | canopen::defaultPDO_incoming (uint16_t CANid, const TPCANRdMsg m) |
void | canopen::defaultPDO_incoming_pos (uint16_t CANid, const TPCANRdMsg m) |
void | canopen::defaultPDO_incoming_status (uint16_t CANid, const TPCANRdMsg m) |
void | canopen::defaultPDOOutgoing (uint16_t CANid, double positionValue) |
void | canopen::defaultPDOOutgoing_interpolated (uint16_t CANid, double positionValue) |
void | canopen::deviceManager () |
const SDOkey | canopen::DISABLE_CODE (0x605C, 0x0) |
void | canopen::disableRPDO (int object) |
void | canopen::disableTPDO (int object) |
const SDOkey | canopen::DRIVERTEMPERATURE (0x22A2, 0x0) |
void | canopen::enableRPDO (int object) |
void | canopen::enableTPDO (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]) |
const SDOkey | canopen::FAULT (0x605E, 0x0) |
void | canopen::getErrors (uint16_t CANid) |
void | canopen::halt (std::string deviceFile, std::chrono::milliseconds syncInterval) |
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::chrono::milliseconds syncInterval) |
void | canopen::initDeviceManagerThread (std::function< void()> const &deviceManager) |
void | canopen::initListenerThread (std::function< void()> const &listener) |
const SDOkey | canopen::IP_TIME_INDEX (0x60C2, 0x2) |
const SDOkey | canopen::IP_TIME_UNITS (0x60C2, 0x1) |
void | canopen::makeRPDOMapping (int object, std::vector< std::string > registers, std::vector< int > sizes, u_int8_t sync_type) |
void | canopen::makeTPDOMapping (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]) |
const SDOkey | canopen::MANUFACTURERDEVICENAME (0x1008, 0x0) |
const SDOkey | canopen::MANUFACTURERHWVERSION (0x1009, 0x0) |
const SDOkey | canopen::MANUFACTURERSOFTWAREVERSION (0x100A, 0x0) |
double | canopen::mdeg2rad (int32_t alpha) |
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) |
std::vector< char > | canopen::obtainManHWVersion (uint16_t CANid, std::shared_ptr< TPCANRdMsg > m) |
std::vector< char > | canopen::obtainManSWVersion (uint16_t CANid, std::shared_ptr< TPCANRdMsg > m) |
std::vector< uint16_t > | canopen::obtainProdCode (uint16_t CANid, std::shared_ptr< TPCANRdMsg > m) |
uint16_t | canopen::obtainRevNr (uint16_t CANid, std::shared_ptr< TPCANRdMsg > m) |
std::vector< uint16_t > | canopen::obtainVendorID (uint16_t CANid) |
bool | canopen::openConnection (std::string devName, std::string baudrate) |
bool | canopen::operator< (const SDOkey &a, const SDOkey &b) |
void | canopen::pdoChanged () |
void | canopen::pre_init () |
void | canopen::processSingleSDO (uint8_t CANid, std::shared_ptr< TPCANRdMsg > message) |
const SDOkey | canopen::QUICK_STOP (0x605A, 0x0) |
int32_t | canopen::rad2mdeg (double phi) |
void | canopen::readErrorsRegister (uint16_t CANid, std::shared_ptr< TPCANRdMsg > m) |
void | canopen::readManErrReg (uint16_t CANid) |
bool | canopen::recover (std::string deviceFile, std::chrono::milliseconds syncInterval) |
void | canopen::requestDataBlock1 (uint8_t CANid) |
void | canopen::requestDataBlock2 (uint8_t CANid) |
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]) |
void | canopen::sendNMT (uint8_t CANid, uint8_t command) |
void | canopen::sendSDO (uint8_t CANid, SDOkey sdo, uint32_t value) |
void | canopen::sendSDO (uint8_t CANid, SDOkey sdo, int32_t value) |
void | canopen::sendSDO (uint8_t CANid, SDOkey sdo, uint16_t value) |
void | canopen::sendSDO (uint8_t CANid, SDOkey sdo, uint8_t value) |
void | canopen::sendSDO_unknown (uint8_t CANid, SDOkey sdo, int32_t value) |
void | canopen::sendSync () |
void | canopen::setMotorState (uint16_t CANid, std::string targetState) |
void | canopen::setNMTState (uint16_t CANid, std::string targetState) |
void | canopen::setObjects () |
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) |
Variables | |
bool | canopen::atFirstInit = true |
std::string | canopen::baudRate |
static std::map< std::string, uint32_t > | canopen::baudrates |
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 |
std::map< uint8_t, Device > | canopen::devices |
static 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 |
std::function< void(uint16_t CANid) > | canopen::geterrors |
HANDLE | canopen::h |
bool | canopen::halt_active |
bool | canopen::halt_negative |
bool | canopen::halt_positive |
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 |
std::map< uint16_t, std::function< void(const TPCANRdMsg m)> > | canopen::incomingPDOHandlers |
const int8_t | canopen::IP_TIME_INDEX_HUNDREDMICROSECONDS = 0xFC |
const int8_t | canopen::IP_TIME_INDEX_MILLISECONDS = 0xFD |
const uint8_t | canopen::MODES_OF_OPERATION_HOMING_MODE = 0x6 |
const uint8_t | canopen::MODES_OF_OPERATION_INTERPOLATED_POSITION_MODE = 0x7 |
const uint8_t | canopen::MODES_OF_OPERATION_PROFILE_POSITION_MODE = 0x1 |
const uint8_t | canopen::MODES_OF_OPERATION_PROFILE_VELOCITY_MODE = 0x3 |
const uint8_t | canopen::MODES_OF_OPERATION_TORQUE_PROFILE_MODE = 0x4 |
const uint8_t | canopen::MODES_OF_OPERATION_VELOCITY_MODE = 0x2 |
static const char *const | canopen::modesDisplay [] |
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 |
TPCANMsg | canopen::NMTmsg |
bool | canopen::no_position |
uint8_t | canopen::operation_mode |
std::string | canopen::operation_mode_param |
BYTE | canopen::protect_msg [] |
bool | canopen::recover_active |
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 |
std::function< void(uint16_t CANid, double positionValue) > | canopen::sendPos |
std::function< void(uint16_t CANid, double positionValue, double velocityValue) > | canopen::sendPosPPMode |
std::function< void(uint16_t CANid, double velocityValue) > | canopen::sendVel |
const uint8_t | canopen::SYNC_TIMEOUT_FACTOR_DISABLE_TIMEOUT = 0 |
std::chrono::milliseconds | canopen::syncInterval |
TPCANMsg | canopen::syncMsg |
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 |
Implementation of canopen driver.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
This program is free software: you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License LGPL as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.
This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License LGPL for more details.
You should have received a copy of the GNU Lesser General Public License LGPL along with this program. If not, see <http://www.gnu.org/licenses/>.
Definition in file canopen.h.