Classes | Namespaces | Functions | Variables
canopen.h File Reference
#include <iostream>
#include <map>
#include <vector>
#include <string>
#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 dependency graph for canopen.h:
This graph shows which files directly or indirectly include this file:

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::controlword (0x6040, 0x0)
void canopen::defaultListener ()
void canopen::deviceManager ()
void canopen::incomingNodeguardHandler (uint8_t CANid, BYTE data[8])
void 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)
double canopen::mdeg2rad (int32_t alpha)
const SDOkey canopen::modes_of_operation (0x6060, 0x0)
const SDOkey canopen::modes_of_operation_display (0x6061, 0x0)
void canopen::modes_of_operation_display_incoming (uint8_t CANid, BYTE data[8])
bool canopen::openConnection (std::string devName)
bool canopen::operator< (const SDOkey &a, const SDOkey &b)
int32_t canopen::rad2mdeg (double phi)
void canopen::schunkDefaultPDO_incoming (uint8_t CANid, const TPCANRdMsg m)
void canopen::schunkDefaultPDOOutgoing (uint16_t CANid, double positionValue)
void canopen::sendNMT (uint8_t command, uint8_t CANid)
void canopen::sendNodeguard (uint8_t CANid)
void canopen::sendSDO (uint8_t CANid, SDOkey sdo)
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, uint8_t value)
void canopen::sendSDO (uint8_t CANid, SDOkey sdo, uint16_t value)
void canopen::sendSync ()
void canopen::setMotorState (uint16_t CANid, std::string targetState)
const SDOkey canopen::statusword (0x6041, 0x0)
void canopen::statusword_incoming (uint8_t CANid, BYTE data[8])
const SDOkey canopen::sync_timeout_factor (0x200e, 0x0)

Variables

const uint16_t canopen::controlword_enable_ip_mode = 16
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_shutdown = 6
const uint16_t canopen::controlword_start_homing = 16
const uint16_t canopen::controlword_switch_on = 7
std::map< SDOkey,
std::function< void(uint8_t
CANid, BYTE data[8])> > 
canopen::incomingDataHandlers
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
const uint8_t canopen::NMT_reset = 0x81
const uint8_t canopen::NMT_start = 0x01
const uint8_t canopen::NMT_stop = 0x02
const uint8_t canopen::sync_timeout_factor_disable_timeout = 0
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


ipa_canopen_core
Author(s): Tobias Sing
autogenerated on Fri Mar 1 2013 18:36:29