Defines | Typedefs | Functions | Variables
epos.h File Reference
#include <stdio.h>
#include <string.h>
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <termios.h>
#include <stdlib.h>
#include <stdint.h>
#include <math.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <arpa/inet.h>
Include dependency graph for epos.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Defines

#define E_HWERR   0x06060000
 Error code: access failed due to an hardware error.
#define E_INTINCOMP   0x06040047
 Error code: general internal incompatibility in the device.
#define E_NMTSTATE   0x0f00ffc0
 Error code: wrong NMT state.
#define E_NOACCES   0x06010000
 Error code: Unsupported access to an object.
#define E_NODEID   0x0f00fb9
 Error code: error in Node-ID.
#define E_NOERR   0x00000000
 Error code: no error.
#define E_NSERV   0x0f00ffbc
 Error code: device not in service mode.
#define E_ONOTEX   0x06020000
 Error code: object does not exist.
#define E_OUTMEM   0x05040005
 Error code: out of memory.
#define E_PARAMINCOMP   0x06040043
 Error code: general parameter incompatibility.
#define E_PARHIGH   0x06090031
 Error code: value of parameter written is too high.
#define E_PARLOW   0x06090032
 Error code: value of parameter written is too low.
#define E_PARREL   0x06090036
 Error code: maximum value is less than minimum value.
#define E_PASSWD   0x0f00ffbe
 Error code: password incorrect.
#define E_PRAGNEX   0x06090030
 Error code: value range of parameter exeeded.
#define E_READONLY   0x06010002
 Error code: Attempt to write a read-only object.
#define E_RS232   0x0f00ffbf
 Error code: rs232 command illegeal.
#define E_SUBINEX   0x06090011
 Error code: subindex does not exist.
#define E_WRITEONLY   0x06010001
 Error code: Attempt to read a write-only object.
#define NTRY   5
 try NTRY times to read one byte from EPOS, the give up
#define TRYSLEEP   (unsigned int)4000
 sleep TRYSLEEP usec between read() from EPOS, if no data available

Typedefs

typedef char BYTE
 8bit type for EPOS data exchange
typedef unsigned long DWORD
 32bit type for EPOS data exchange
typedef unsigned short WORD
 16bit type for EPOS data exchange

Functions

int changeEPOSstate (int state)
 change EPOS state ==> firmware spec 8.1.3
int checkEPOS ()
int checkEPOSerror ()
 check global variable E_error for EPOS error code
int checkEPOSstate ()
 check EPOS status, return state according to firmware spec 8.1.1
int closeEPOS ()
int doHoming (int method, long int start)
 does a homing move. Give homing mode (see firmware 9.3) and start position
int monitorHomingStatus ()
 as monitorStatus(), but also waits for Homing Attained' signal
int monitorStatus ()
 reads position, velocity and current and displays them in an endless loop. Returns after target position has been reached
int moveAbsolute (long int steps)
 set OpMode to ProfilePosition and make absolute movement
int moveRelative (long int steps)
 set OpMode to ProfilePosition and make relative movement
int moveVelocity (int32_t steps)
 set OpMode to ProfileVelocity and make movement
int openEPOS (char *device)
int openTCPEPOS (char *ip, short unsigned port)
int printEPOScontrolword (WORD controlword)
 pretty-print Controlword
int printEPOSstate ()
 pretty-print EPOS state
int printEPOSstatusword (WORD statusword)
 pretty-print Statusword
int readActualCurrent (short *val)
 read actual current; 14.1.69
int readActualPosition (long *val)
 read actual position; 14.1.62
int readActualVelocity (long *val)
 read actual position; 14.1.68
int readControlword (WORD *w)
 read EPOS control word (firmware spec 14.1.57)
int readDemandPosition (long *val)
 read actual position; 14.1.61
int readDemandVelocity (long *val)
 read actual position; 14.1.67
int readDeviceName (char *name)
 ask for device name, device name is placed in 'name' (string must be big enough, NO CHECKING!!)
int readDInputPolarity (WORD *w)
 read digital input polarity mask
int readOpMode ()
 read and returns EPOS mode of operation -- 14.1.60 here, RETURN(0) MEANS ERROR! '-1' is a valid OpMode, but 0 is not!
int readPositionWindow (unsigned long int *value)
 read position window; 14.1.64
int readRS232timeout ()
 ask for RS232 timeout; firmware spec 14.1.35
int readStatusword (WORD *eposStatus)
 read Statusword; 14.1.58
int readSWversion ()
 example from EPOS com. guide: ask EPOS for software version
int readTargetPosition (long *val)
 read target position; 14.1.70
int set_speed_profile (unsigned int max_velocity, unsigned int acceleration=1000, unsigned int deceleration=1000, bool trapezoidal=true)
int setHomePolarity (int pol)
 set home switch polarity -- firmware spec 14.1.47
int setOpMode (int OpMode)
 set EPOS mode of operation -- 14.1.59
int waitForTarget (unsigned int t)
 waits for positoning to finish, argument is timeout in seconds. give timeout==0 to disable timeout
int writePositionWindow (unsigned long int value)
 write position window; 14.1.64

Variables

DWORD E_error
 EPOS global error status.
int sp

Detailed Description

header file for libEPOS functions

mh, july 2006

Definition in file epos.h.


Define Documentation

#define E_HWERR   0x06060000

Error code: access failed due to an hardware error.

Definition at line 37 of file epos.h.

#define E_INTINCOMP   0x06040047

Error code: general internal incompatibility in the device.

Definition at line 36 of file epos.h.

#define E_NMTSTATE   0x0f00ffc0

Error code: wrong NMT state.

Definition at line 42 of file epos.h.

#define E_NOACCES   0x06010000

Error code: Unsupported access to an object.

Definition at line 32 of file epos.h.

#define E_NODEID   0x0f00fb9

Error code: error in Node-ID.

Definition at line 46 of file epos.h.

#define E_NOERR   0x00000000

Error code: no error.

Definition at line 28 of file epos.h.

#define E_NSERV   0x0f00ffbc

Error code: device not in service mode.

Definition at line 45 of file epos.h.

#define E_ONOTEX   0x06020000

Error code: object does not exist.

Definition at line 29 of file epos.h.

#define E_OUTMEM   0x05040005

Error code: out of memory.

Definition at line 31 of file epos.h.

#define E_PARAMINCOMP   0x06040043

Error code: general parameter incompatibility.

Definition at line 35 of file epos.h.

#define E_PARHIGH   0x06090031

Error code: value of parameter written is too high.

Definition at line 39 of file epos.h.

#define E_PARLOW   0x06090032

Error code: value of parameter written is too low.

Definition at line 40 of file epos.h.

#define E_PARREL   0x06090036

Error code: maximum value is less than minimum value.

Definition at line 41 of file epos.h.

#define E_PASSWD   0x0f00ffbe

Error code: password incorrect.

Definition at line 44 of file epos.h.

#define E_PRAGNEX   0x06090030

Error code: value range of parameter exeeded.

Definition at line 38 of file epos.h.

#define E_READONLY   0x06010002

Error code: Attempt to write a read-only object.

Definition at line 34 of file epos.h.

#define E_RS232   0x0f00ffbf

Error code: rs232 command illegeal.

Definition at line 43 of file epos.h.

#define E_SUBINEX   0x06090011

Error code: subindex does not exist.

Definition at line 30 of file epos.h.

#define E_WRITEONLY   0x06010001

Error code: Attempt to read a write-only object.

Definition at line 33 of file epos.h.

#define NTRY   5

try NTRY times to read one byte from EPOS, the give up

Definition at line 61 of file epos.h.

#define TRYSLEEP   (unsigned int)4000

sleep TRYSLEEP usec between read() from EPOS, if no data available

Definition at line 64 of file epos.h.


Typedef Documentation

typedef char BYTE

8bit type for EPOS data exchange

Definition at line 55 of file epos.h.

typedef unsigned long DWORD

32bit type for EPOS data exchange

Definition at line 52 of file epos.h.

typedef unsigned short WORD

16bit type for EPOS data exchange

Definition at line 53 of file epos.h.


Function Documentation

int changeEPOSstate ( int  state)

change EPOS state ==> firmware spec 8.1.3

Definition at line 667 of file epos.cpp.

int checkEPOS ( )

check if the connection to EPOS is alive

check whether the socket connection to EPOS is established

Return values:
0success
-1failure

Definition at line 365 of file epos.cpp.

int checkEPOSerror ( )

check global variable E_error for EPOS error code

Definition at line 1951 of file epos.cpp.

int checkEPOSstate ( )

check EPOS status, return state according to firmware spec 8.1.1

check EPOS state, firmware spec 8.1.1

Returns:
EPOS status as defined in firmware specification 8.1.1

Definition at line 508 of file epos.cpp.

int closeEPOS ( )

close the connection to EPOS

closes connection socket of EPOS device

Return values:
0success
-1failure

Definition at line 354 of file epos.cpp.

int doHoming ( int  method,
long int  start 
)

does a homing move. Give homing mode (see firmware 9.3) and start position

Definition at line 1468 of file epos.cpp.

as monitorStatus(), but also waits for Homing Attained' signal

Definition at line 1844 of file epos.cpp.

int monitorStatus ( )

reads position, velocity and current and displays them in an endless loop. Returns after target position has been reached

Definition at line 1773 of file epos.cpp.

int moveAbsolute ( long int  steps)

set OpMode to ProfilePosition and make absolute movement

Definition at line 1652 of file epos.cpp.

int moveRelative ( long int  steps)

set OpMode to ProfilePosition and make relative movement

Definition at line 1605 of file epos.cpp.

int moveVelocity ( int32_t  steps)

set OpMode to ProfileVelocity and make movement

Definition at line 1711 of file epos.cpp.

int openEPOS ( char *  dev)

open the connection to EPOS

establish the connection to EPOS via RS232 connection

Parameters:
devstring describing the device on which the EPOS is connected to, e.g. "/dev/ttyS0"
Return values:
0success
-1failure

Definition at line 234 of file epos.cpp.

int openTCPEPOS ( char *  ip,
short unsigned  port 
)

open the connection to EPOS via RS232-over-TCP/IP (LSW special)

establish the connection to EPOS via a TCP/IP tunneled RS232 connection

Parameters:
ipstring describing the IP address on which the EPOS is connected to, e.g. "192.168.1.100"
portshort unsigned int giving the TCP port number on the device 'IP'
Return values:
0success
-1failure

Definition at line 303 of file epos.cpp.

int printEPOScontrolword ( WORD  controlword)

pretty-print Controlword

Definition at line 951 of file epos.cpp.

int printEPOSstate ( )

pretty-print EPOS state

Definition at line 639 of file epos.cpp.

pretty-print Statusword

pretty-print Statusword to stdout

Parameters:
sWORD variable holding the statusword

Definition at line 428 of file epos.cpp.

int readActualCurrent ( short *  val)

read actual current; 14.1.69

int readActualPosition ( long *  pos)

read actual position; 14.1.62

read actual position; firmware description 14.1.62

Return values:
0success
<0some error, check with checkEPOSerror()

Definition at line 1108 of file epos.cpp.

int readActualVelocity ( long *  val)

read actual position; 14.1.68

Definition at line 1229 of file epos.cpp.

int readControlword ( WORD w)

read EPOS control word (firmware spec 14.1.57)

Definition at line 921 of file epos.cpp.

int readDemandPosition ( long *  val)

read actual position; 14.1.61

Definition at line 1073 of file epos.cpp.

int readDemandVelocity ( long *  val)

read actual position; 14.1.67

Definition at line 1198 of file epos.cpp.

int readDeviceName ( char *  str)

ask for device name, device name is placed in 'name' (string must be big enough, NO CHECKING!!)

readDeviceName: read manufactor device name string firmware

Parameters:
strpreviously allocated string, will be filled with device name
Return values:
0success
-1error

Definition at line 1349 of file epos.cpp.

int readDInputPolarity ( WORD w)

read digital input polarity mask

Definition at line 839 of file epos.cpp.

int readOpMode ( )

read and returns EPOS mode of operation -- 14.1.60 here, RETURN(0) MEANS ERROR! '-1' is a valid OpMode, but 0 is not!

read mode of operation --- 14.1.60

Returns:
RETURN(0) MEANS ERROR! -1 is a valid OpMode, but 0 is not!

Definition at line 1027 of file epos.cpp.

int readPositionWindow ( unsigned long int *  value)

read position window; 14.1.64

Definition at line 1139 of file epos.cpp.

ask for RS232 timeout; firmware spec 14.1.35

Definition at line 1385 of file epos.cpp.

int readStatusword ( WORD status)

read Statusword; 14.1.58

read EPOS status word

Parameters:
statuspointer to WORD, the content of EPOS statusword will be placed there
Return values:
0success
-1failure

Definition at line 392 of file epos.cpp.

int readSWversion ( )

example from EPOS com. guide: ask EPOS for software version

firmware spec 14.1.33 returns software version as HEX **

Definition at line 805 of file epos.cpp.

int readTargetPosition ( long *  val)

read target position; 14.1.70

read EPOS target position; firmware description 14.1.70

Parameters:
valpointer to long int, will be filled with EPOS target position
Return values:
0success
-1error

Definition at line 1307 of file epos.cpp.

int set_speed_profile ( unsigned int  max_velocity,
unsigned int  acceleration = 1000,
unsigned int  deceleration = 1000,
bool  trapezoidal = true 
)

Definition at line 1409 of file epos.cpp.

int setHomePolarity ( int  pol)

set home switch polarity -- firmware spec 14.1.47

Definition at line 874 of file epos.cpp.

int setOpMode ( int  OpMode)

set EPOS mode of operation -- 14.1.59

Definition at line 1000 of file epos.cpp.

int waitForTarget ( unsigned int  t)

waits for positoning to finish, argument is timeout in seconds. give timeout==0 to disable timeout

Definition at line 1924 of file epos.cpp.

int writePositionWindow ( unsigned long int  value)

write position window; 14.1.64

Definition at line 1169 of file epos.cpp.


Variable Documentation

EPOS global error status.

EPOS global error status

Definition at line 131 of file epos.cpp.

int sp

serial port file descriptor

Definition at line 130 of file epos.cpp.



epos_driver
Author(s): Tomasz Kucner , Martin Magnusson , Hakan Almqvist , Marcus Hauser
autogenerated on Fri Aug 28 2015 10:38:28