Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
CEpos2 Class Reference

Implementation of a driver for EPOS2 Motor Controller. More...

#include <Epos2.h>

Public Types

Operation Modes - Names

enum  epos_states {
  FAULT, START, NOT_READY_TO_SWITCH_ON, SWITCH_ON_DISABLED,
  READY_TO_SWITCH_ON, SWITCH_ON, REFRESH, MEASURE_INIT,
  OPERATION_ENABLE, QUICK_STOP, QUICK_STOP_ACTIVE_DISABLE, QUICK_STOP_ACTIVE_ENABLE
}
 
enum  epos_opmodes {
  NO_OPERATION = 99, VELOCITY = -2, POSITION = -1, PROFILE_VELOCITY = 3,
  PROFILE_POSITION = 1, INTERPOLATED_PROFILE_POSITION = 7, HOMING = 6
}
 
enum  epos_posmodes { HALT, ABSOLUTE, RELATIVE }
 

Public Member Functions

 CEpos2 (int8_t nodeId=0x00)
 Constructor. More...
 
void close ()
 Disconnects hardware. More...
 
void init ()
 Connects hardware. More...
 
 ~CEpos2 ()
 Destructor. More...
 
State Management
long getState ()
 function to get current controller's state More...
 
void shutdown ()
 function to reach ready_to_switch_on state More...
 
void switchOn ()
 function to reach switch_on state More...
 
void quickStop ()
 function to reach switch_on state More...
 
void enableOperation ()
 function to reach operation_enable state and enables power on motor More...
 
void disableOperation ()
 function to reach switch_on and disables power on motor More...
 
void disableVoltage ()
 function to reach switch_on_disabled state More...
 
void faultReset ()
 function to reach switch_on_disabled state after a FAULT More...
 
Operation Modes Management
long getOperationMode ()
 function to know which operation mode is set More...
 
std::string getOpModeDescription (long opmode)
 function to show the name of the operation mode More...
 
void setOperationMode (long opmode)
 function to set the operation mode More...
 
void enableController ()
 function to facititate transitions from the start of the controller to switch it on More...
 
void enableMotor (long opmode)
 function to facititate transitions from switched on to operation enabled More...
 
bool isTargetReached ()
 function to know if the motor has reached the target position or velocity More...
 
Operation Mode - velocity
long getTargetVelocity ()
 function to GET the target velocity This function gets the target velocity of velocity operation mode More...
 
void setTargetVelocity (long velocity)
 function to SET the target velocity More...
 
void startVelocity ()
 function to move the motor in Velocity mode More...
 
void stopVelocity ()
 function to stop the motor in velocity mode More...
 
Operation Mode - profile_position
long getTargetProfilePosition ()
 function to GET the target position More...
 
void setTargetProfilePosition (long position)
 function to SET the target position More...
 
void startProfilePosition (epos_posmodes mode, bool blocking=true, bool wait=true, bool new_point=true)
 function to move the motor to a position in profile position mode More...
 
Operation Mode - profile_velocity
long getTargetProfileVelocity ()
 [OPMODE=profile_velocity] function to get the velocity More...
 
void setTargetProfileVelocity (long velocity)
 [OPMODE=profile_velocity] function to set the velocity More...
 
void startProfileVelocity ()
 [OPMODE=profile_velocity] function to move the motor in a velocity More...
 
void stopProfileVelocity ()
 [OPMODE=profile_velocity] function to stop the motor More...
 
Operation Mode - current
long getTargetCurrent ()
 [OPMODE=current] function to GET the target current More...
 
void setTargetCurrent (long current)
 [OPMODE=current] function to SET the target current More...
 
void startCurrent ()
 [OPMODE=current] function to move the motor in current mode More...
 
void stopCurrent ()
 [OPMODE=current] function to stop the motor in current mode More...
 
Operation Mode - home
void setHome ()
 function to set a Home position with user interaction More...
 
void setHomePosition (long home_position_qc)
 function to set a Home position More...
 
long getHomePosition ()
 function to get the Home position More...
 
Control Tuning

Motion Control Configuration

long getCurrentPGain ()
 function to get P Current Gain More...
 
void setCurrentPGain (long gain)
 function to set P Current Gain More...
 
long getCurrentIGain ()
 function to get I Current Gain More...
 
void setCurrentIGain (long gain)
 function to set I Current Gain More...
 
long getVelocityPGain ()
 function to get P Velocity Gain More...
 
void setVelocityPGain (long gain)
 function to set P Velocity Gain More...
 
long getVelocityIGain ()
 function to get I Velocity Gain More...
 
void setVelocityIGain (long gain)
 function to set I Velocity Gain More...
 
long getVelocitySetPointFactorPGain ()
 function to GET Speed Regulator Set Point Factor P Velocity Gain More...
 
void setVelocitySetPointFactorPGain (long gain)
 function to SET Speed Regulator Set Point Factor P Velocity Gain More...
 
long getPositionPGain ()
 function to get P Position Gain More...
 
void setPositionPGain (long gain)
 function to set P Position Gain More...
 
long getPositionIGain ()
 function to get I Position Gain More...
 
void setPositionIGain (long gain)
 function to set I Position Gain More...
 
long getPositionDGain ()
 function to get D Position Gain More...
 
void setPositionDGain (long gain)
 function to set D Position Gain More...
 
long getPositionVFFGain ()
 function to get Velocity Feed Forward Position Gain More...
 
void setPositionVFFGain (long gain)
 function to set Velocity Feed Forward Position Gain More...
 
long getPositionAFFGain ()
 function to get Acceleration Feed Forward Position Gain More...
 
void setPositionAFFGain (long gain)
 function to set Acceleration Feed Forward Position Gain More...
 
void getControlParameters (long &cp, long &ci, long &vp, long &vi, long &vspf, long &pp, long &pi, long &pd, long &pv, long &pa)
 function to get all control parameters More...
 
void setControlParameters (long cp, long ci, long vp, long vi, long vspf, long pp, long pi, long pd, long pv, long pa)
 function to set all control parameters More...
 
void printControlParameters (long cp, long ci, long vp, long vi, long vspf, long pp, long pi, long pd, long pv, long pa)
 function to show all control parameters More...
 
Profile

For Profile Position and Profile Velocity modes.

long getProfileVelocity (void)
 function to GET the velocity of the Velocity Profile More...
 
void setProfileVelocity (long velocity)
 function to SET the velocity of the Velocity Profile More...
 
long getProfileMaxVelocity (void)
 function to GET the Max Velocity allowed in Profile More...
 
void setProfileMaxVelocity (long velocity)
 function to SET the Max Velocity allowed in Profile More...
 
long getProfileAcceleration (void)
 function to GET the Acceleration in profile More...
 
void setProfileAcceleration (long acceleration)
 function to SET the Acceleration in profile More...
 
long getProfileDeceleration (void)
 function to GET the Deceleration in profile More...
 
void setProfileDeceleration (long deceleration)
 function to SET the Deceleration in profile More...
 
long getProfileQuickStopDecel (void)
 function to GET the Quick Stop Deceleration in profile More...
 
void setProfileQuickStopDecel (long deceleration)
 function to SET the Quick Stop Deceleration in profile More...
 
long getProfileType (void)
 function to GET the type in profile More...
 
void setProfileType (long type)
 function to SET the type in profile More...
 
long getMaxAcceleration (void)
 function to GET Max Acceleration More...
 
void setMaxAcceleration (long max_acceleration)
 function to SET Max Acceleration More...
 
void getProfileData (long &vel, long &maxvel, long &acc, long &dec, long &qsdec, long &maxacc, long &type)
 function to GET all data of the velocity profile More...
 
void setProfileData (long vel, long maxvel, long acc, long dec, long qsdec, long maxacc, long type)
 function to SET all data of the velocity profile More...
 
Sensor configuration
long getEncoderPulseNumber ()
 function to GET the Encoder Pulses More...
 
void setEncoderPulseNumber (long pulses)
 function to SET the Encoder Pulses More...
 
long getEncoderType ()
 function to GET the Encoder Pulses More...
 
void setEncoderType (long type)
 function to SET the Encoder type More...
 
long getEncoderPolarity ()
 function to GET the Encoder Pulses More...
 
void setEncoderPolarity (long polarity)
 function to SET the Encoder polarity More...
 
void getEncoderParameters (long &pulses, long &type, long &polarity)
 function to GET encoder parameters More...
 
void setEncoderParameters (long pulses, long type, long polarity)
 function to SET encoder parameters More...
 
Motor
long getMotorType ()
 function to GET Motor type More...
 
void setMotorType (long type)
 function to SET Motor type More...
 
long getMotorContinuousCurrentLimit ()
 function to GET Motor Continous Current Limit More...
 
void setMotorContinuousCurrentLimit (long current_mA)
 function to SET Motor Continous Current Limit More...
 
long getMotorOutputCurrentLimit ()
 function to GET Motor Output Current Limit More...
 
void setMotorOutputCurrentLimit (long current_mA)
 function to SET Motor Output Current Limit More...
 
long getMotorPolePairNumber ()
 function to GET Motor Pole Pair Number More...
 
void setMotorPolePairNumber (char pole_pairs)
 function to SET Motor Pole Pair Number More...
 
long getThermalTimeCtWinding ()
 function to GET Motor Thermal Time Constant Winding More...
 
void setThermalTimeCtWinding (long time_ds)
 function to SET Motor Thermal Time Constant Winding More...
 
void getMotorParameters (long &type, long &current_c_mA, long &current_out_mA, char &pole_pairs, long &time_ds)
 function to GET encoder parameters More...
 
void setMotorParameters (long type, long current_c_mA, long current_out_mA, char pole_pairs, long time_ds)
 function to SET motor parameters More...
 
Communication configuration
long getRS232Baudrate ()
 function to GET the RS232 Baudrate More...
 
void setRS232Baudrate (long baudrate)
 function to SET the RS232 Baudrate More...
 
long getRS232FrameTimeout ()
 function to GET the RS232 Frame Timeout More...
 
void setRS232FrameTimeout (long timeout)
 function to SET the RS232 Frame Timeout More...
 
long getUSBFrameTimeout ()
 function to GET the USB Frame Timeout More...
 
void setUSBFrameTimeout (long timeout)
 function to SET the USB Frame Timeout More...
 
Position parameters configuration
long getMaxFollowingError ()
 function to GET the Max Following Error More...
 
void setMaxFollowingError (long follerror)
 function to SET the Max Following Error More...
 
long getMinPositionLimit ()
 function to GET the Min Position Limit More...
 
void setMinPositionLimit (long limit)
 function to SET the Min Position Limit More...
 
long getMaxPositionLimit ()
 function to GET the Max Position Limit More...
 
void setMaxPositionLimit (long limit)
 function to SET the Max Position Limit More...
 
void disablePositionLimits (void)
 function to DISABLE Position Limits More...
 
long getPositionWindow ()
 function to get Position Window More...
 
void setPositionWindow (long window_qc)
 function to set Position Window More...
 
long getPositionWindowTime ()
 function to get Position Window Time More...
 
void setPositionWindowTime (long time_ms)
 function to set Position Window Time More...
 
long getVelocityWindow ()
 function to get Velocity Window More...
 
void setVelocityWindow (long window_rm)
 function to set Velocity Window More...
 
long getVelocityWindowTime ()
 function to get Velocity Window Time More...
 
void setVelocityWindowTime (long time_ms)
 function to set Velocity Window Time More...
 
Dimension and notation configuration
long getPositionNotationIndex ()
 function to get Position Notation Index More...
 
void setPositionNotationIndex (long notation)
 function to set Position Notation Index More...
 
long getVelocityNotationIndex ()
 function to get Velocity Notation Index More...
 
void setVelocityNotationIndex (long notation)
 function to set Velocity Notation Index More...
 
long getAccelerationNotationIndex ()
 function to get Acceleration Notation Index More...
 
void setAccelerationNotationIndex (long notation)
 function to set Acceleration Notation Index More...
 
long getPositionDimensionIndex ()
 function to get Position Dimension Index More...
 
void setPositionDimensionIndex (long Dimension)
 function to set Position Dimension Index More...
 
long getVelocityDimensionIndex ()
 function to get Velocity Dimension Index More...
 
void setVelocityDimensionIndex (long Dimension)
 function to set Velocity Dimension Index More...
 
long getAccelerationDimensionIndex ()
 function to get Acceleration Dimension Index More...
 
void setAccelerationDimensionIndex (long Dimension)
 function to set Acceleration Dimension Index More...
 

Private Member Functions

long getNegativeLong (long number)
 function to make a unsigned long signed More...
 
void p (const char *text)
 function to make a unsigned long signed More...
 
void p (const std::stringstream &text)
 
Communication low level
void openDevice ()
 open EPOS2 device using CFTDI More...
 
int32_t readObject (int16_t index, int8_t subindex)
 function to read an object from the EPOS2 More...
 
int writeObject (int16_t index, int8_t subindex, int32_t data)
 function to write an object to the EPOS2 More...
 
void sendFrame (int16_t *frame)
 function send a frame to EPOS2 More...
 
void receiveFrame (uint16_t *ans_frame)
 function receive a frame from EPOS2 More...
 
int16_t computeChecksum (int16_t *pDataArray, int16_t numberOfWords)
 function to compute EPOS2 checksum More...
 

Private Attributes

int8_t node_id
 
bool verbose
 

Static Private Attributes

static Ftdi::Context ftdi
 a reference to the FTDI USB device More...
 
static bool ftdi_initialized = false
 

Info

static const std::string error_names []
 Strings of generic error descriptions. More...
 
static const int error_codes []
 error integer codes More...
 
static const std::string error_descriptions []
 error descriptions More...
 
long readVelocity ()
 function to read motor average velocity More...
 
long readVelocitySensorActual ()
 function to read velocity sensor actual More...
 
long readVelocityDemand ()
 function to read velocity demand More...
 
long readVelocityActual ()
 function to read velocity sensor actual More...
 
long readCurrent ()
 function to read motor current More...
 
long readCurrentAveraged ()
 function to read motor averaged current More...
 
long readCurrentDemanded ()
 function to read current demanded More...
 
int32_t readPosition ()
 function to read motor position More...
 
long readStatusWord ()
 function to read EPOS2 StatusWord More...
 
long readEncoderCounter ()
 function to read the Encoder Counter More...
 
long readEncoderCounterAtIndexPulse ()
 function to read the Encoder Counter at index pulse More...
 
long readHallsensorPattern ()
 function to read the Hall Sensor Pattern More...
 
long readFollowingError ()
 function to read the Following Error More...
 
void getMovementInfo ()
 prints information about movement More...
 
char readError ()
 function to read an Error information More...
 
void readErrorHistory (long *error[5])
 function to read last 5 errors More...
 
std::string searchErrorDescription (long error_code)
 given an error code it returns its description More...
 
long readVersionSoftware ()
 function to read the software version More...
 
long readVersionHardware ()
 function to read the hardware version More...
 

Utilities

long getAnalogOutput1 ()
 function to get the value in the Analog Output1 More...
 
void setAnalogOutput1 (long voltage_mV)
 function to set analog output 1 More...
 
void saveParameters ()
 function to save all parameters in EEPROM More...
 
void restoreDefaultParameters ()
 function to restore default parameters of EPOS2. More...
 
bool getVerbose ()
 
void setVerbose (bool verbose)
 
long getPositionMarker (int buffer=0)
 gets the position marked by the sensor More...
 
void setPositionMarker (char polarity=0, char edge_type=0, char mode=0, char digitalIN=2)
 Sets the configuration of a marker position. More...
 
void waitPositionMarker ()
 wait for marker position reached More...
 
void setHoming (int home_method=11, int speed_pos=100, int speed_zero=100, int acc=1000, int digitalIN=2)
 Sets the configuration of a homing operation. More...
 
void doHoming (bool blocking=false)
 starts a homing operation More...
 
void stopHoming ()
 stops a homing operation More...
 
int getDigInState (int digitalIN=2)
 Gives the state of a certain digital Input. More...
 
int getDigInStateMask ()
 Gives Digital Inputs State Mask. More...
 
int getDigInFuncMask ()
 Gives Digital Inputs Functionalities Mask. More...
 
int getDigInPolarity ()
 Gives Digital Inputs Polarity Mask. More...
 
int getDigInExecutionMask ()
 Gives Digital Inputs Execution Mask. More...
 
static void * threadTargetReached (void *param)
 Thread listens to target reached. More...
 

Detailed Description

Implementation of a driver for EPOS2 Motor Controller.

Author
Martí Morta (mmorta @ iri.upc.edu)
Version
1.0
Date
august 2009

This class is a low level driver to manage Maxon Motor EPOS2 Controller. It is tested in EPOS2 50/5 using firmware Epos_2110h_6322h_0000h_0000h.bin. All functions objects in controller are in the document EPOS2 Firmware Specification of December 2008 Edition/ document number 821384-02.

It implements all functions to use one unique controller and adds other useful features to simplify some tasks.

Warning
Units are in default (position:qc, velocity: [rev/min], acceleration: [rev/min/s]) if you change dimension or notation index you will have to take them into account.
This class doesn't implements operation modes that need other controllers or * external signals. Neither CAN, SDO, PDO functions of the controller.
Todo:
  • Smarter ReadObject (16-32 bits)
  • Current mode functions
  • Sensor functions
  • Motor functions
  • Utilities functions: window/window times, notation/dimension index, analog Output
Examples:
configtest.cpp, test_epos2.cpp, test_homing.cpp, test_like_h3d.cpp, test_marker.cpp, and test_positions.cpp.

Definition at line 60 of file Epos2.h.

Member Enumeration Documentation

EPOS2 firmware (9) operation modes.

Note
"no_operation" is an arbitrary number
Enumerator
NO_OPERATION 
VELOCITY 
POSITION 
PROFILE_VELOCITY 
PROFILE_POSITION 
INTERPOLATED_PROFILE_POSITION 
HOMING 

Definition at line 334 of file Epos2.h.

EPOS2 firmware profile position modes

Enumerator
HALT 
ABSOLUTE 
RELATIVE 

Definition at line 341 of file Epos2.h.

EPOS2 firmware states

Enumerator
FAULT 
START 
NOT_READY_TO_SWITCH_ON 
SWITCH_ON_DISABLED 
READY_TO_SWITCH_ON 
SWITCH_ON 
REFRESH 
MEASURE_INIT 
OPERATION_ENABLE 
QUICK_STOP 
QUICK_STOP_ACTIVE_DISABLE 
QUICK_STOP_ACTIVE_ENABLE 

Definition at line 325 of file Epos2.h.

Constructor & Destructor Documentation

CEpos2::CEpos2 ( int8_t  nodeId = 0x00)

Constructor.

Definition at line 33 of file Epos2.cpp.

CEpos2::~CEpos2 ( )

Destructor.

Definition at line 39 of file Epos2.cpp.

Member Function Documentation

void CEpos2::close ( )

Disconnects hardware.

Examples:
configtest.cpp, test_epos2.cpp, test_homing.cpp, test_like_h3d.cpp, test_marker.cpp, and test_positions.cpp.

Definition at line 58 of file Epos2.cpp.

int16_t CEpos2::computeChecksum ( int16_t *  pDataArray,
int16_t  numberOfWords 
)
private

function to compute EPOS2 checksum

This function is implemented in the EPOS2 Communication Guide.

Parameters
pDataArray
numberOfWords
Returns
checksum (16 bits)

Definition at line 366 of file Epos2.cpp.

void CEpos2::disableOperation ( )

function to reach switch_on and disables power on motor

Transition: 5 EPOS2 State Machine with libEPOS2 functions See EPOS2 state machine

Examples:
configtest.cpp.

Definition at line 549 of file Epos2.cpp.

void CEpos2::disablePositionLimits ( void  )

function to DISABLE Position Limits

This function disables Position Limits it writes min= -2147483648 max= 2147483647

Definition at line 1402 of file Epos2.cpp.

void CEpos2::disableVoltage ( )

function to reach switch_on_disabled state

Transition: 7,9,10,12 EPOS2 State Machine with libEPOS2 functions See EPOS2 state machine

Definition at line 533 of file Epos2.cpp.

void CEpos2::doHoming ( bool  blocking = false)

starts a homing operation

Options had to be set with setHoming

Examples:
test_homing.cpp.

Definition at line 1577 of file Epos2.cpp.

void CEpos2::enableController ( )

function to facititate transitions from the start of the controller to switch it on

This function does all transitions from start to switched on to be able to work with the controller.

Examples:
configtest.cpp, test_epos2.cpp, test_homing.cpp, test_like_h3d.cpp, test_marker.cpp, and test_positions.cpp.

Definition at line 632 of file Epos2.cpp.

void CEpos2::enableMotor ( long  opmode)

function to facititate transitions from switched on to operation enabled

This function does all transitions from switched on to operation enabled work with the motor.

        \param opmode desired operation mode (velocity, profile_position,

profile_velocity,current,homing)

Examples:
configtest.cpp, test_epos2.cpp, test_homing.cpp, test_like_h3d.cpp, and test_positions.cpp.

Definition at line 696 of file Epos2.cpp.

void CEpos2::enableOperation ( )

function to reach operation_enable state and enables power on motor

Transition: 4,16 EPOS2 State Machine with libEPOS2 functions See EPOS2 state machine

Examples:
configtest.cpp.

Definition at line 557 of file Epos2.cpp.

void CEpos2::faultReset ( )

function to reach switch_on_disabled state after a FAULT

This function does the transition to reach switch_on_disabled state after a FAULT. It is necessary to clear Can passive mode error at the start of EPOS controller

Transition: 15 EPOS2 State Machine with libEPOS2 functions See EPOS2 state machine

Definition at line 565 of file Epos2.cpp.

long CEpos2::getAccelerationDimensionIndex ( )

function to get Acceleration Dimension Index

This function gets Acceleration Dimension Index

Returns
Acceleration Dimension Index

Definition at line 1447 of file Epos2.cpp.

long CEpos2::getAccelerationNotationIndex ( )

function to get Acceleration Notation Index

This function gets Acceleration Notation Index

Returns
Acceleration Notation Index

Definition at line 1435 of file Epos2.cpp.

long CEpos2::getAnalogOutput1 ( )

function to get the value in the Analog Output1

This function gets the value in the Analog Output1, to know which Voltage is giving this output [mV]

Returns
actual output

Definition at line 1506 of file Epos2.cpp.

void CEpos2::getControlParameters ( long &  cp,
long &  ci,
long &  vp,
long &  vi,
long &  vspf,
long &  pp,
long &  pi,
long &  pd,
long &  pv,
long &  pa 
)

function to get all control parameters

gets all control parameters and save them into user variables

Return values
cpCurrent Proportional
ciCurrent Integral
vpVelocity Proportional
viVelocity Integral
vspfVelocity Set Point Factor P Gain
ppPostition Proportional
piPosition Integral
pdPosition Derivative
pvPosition Velocity Feed Forward Factor
paPosition Acceleration Feed Forward Factor
Examples:
configtest.cpp.

Definition at line 977 of file Epos2.cpp.

long CEpos2::getCurrentIGain ( )

function to get I Current Gain

This function gets the actual I Current Gain

Returns
gain (must be between 0 and 32767)

Definition at line 882 of file Epos2.cpp.

long CEpos2::getCurrentPGain ( )

function to get P Current Gain

This function gets the actual P Current Gain

Returns
gain

Definition at line 872 of file Epos2.cpp.

int CEpos2::getDigInExecutionMask ( )

Gives Digital Inputs Execution Mask.

Returns
execution mask [FW table 111]
Examples:
test_homing.cpp, and test_marker.cpp.

Definition at line 1618 of file Epos2.cpp.

int CEpos2::getDigInFuncMask ( )

Gives Digital Inputs Functionalities Mask.

Returns
functionalities mask [FW table 99]
Examples:
test_homing.cpp, and test_marker.cpp.

Definition at line 1608 of file Epos2.cpp.

int CEpos2::getDigInPolarity ( )

Gives Digital Inputs Polarity Mask.

Returns
functionalities polarity mask [FW table 100]
Examples:
test_homing.cpp, and test_marker.cpp.

Definition at line 1613 of file Epos2.cpp.

int CEpos2::getDigInState ( int  digitalIN = 2)

Gives the state of a certain digital Input.

Returns
0: inactive, 1: active(depending on polarity=0)
Examples:
test_homing.cpp, and test_marker.cpp.

Definition at line 1598 of file Epos2.cpp.

int CEpos2::getDigInStateMask ( )

Gives Digital Inputs State Mask.

Returns
state mask [FW table 98]
Examples:
test_homing.cpp, and test_marker.cpp.

Definition at line 1603 of file Epos2.cpp.

void CEpos2::getEncoderParameters ( long &  pulses,
long &  type,
long &  polarity 
)

function to GET encoder parameters

Return values
&pulses
&type
&polarity

Definition at line 1339 of file Epos2.cpp.

long CEpos2::getEncoderPolarity ( )

function to GET the Encoder Pulses

This function gets the Encoder Pulses

Returns
Encoder Pulses

Definition at line 1333 of file Epos2.cpp.

long CEpos2::getEncoderPulseNumber ( )

function to GET the Encoder Pulses

This function gets the Encoder Pulses

Returns
Encoder Pulses

Definition at line 1317 of file Epos2.cpp.

long CEpos2::getEncoderType ( )

function to GET the Encoder Pulses

This function gets the Encoder Pulses

Returns
Encoder Pulses

Definition at line 1327 of file Epos2.cpp.

long CEpos2::getHomePosition ( )

function to get the Home position

This function gets a home position.

Returns
home position

Definition at line 1631 of file Epos2.cpp.

long CEpos2::getMaxAcceleration ( void  )

function to GET Max Acceleration

This function gets Max Acceleration [rev/min/s]

Returns
acceleration

Definition at line 1089 of file Epos2.cpp.

long CEpos2::getMaxFollowingError ( )

function to GET the Max Following Error

This function gets the Max following error [qc]

Returns
Max Following Error

Definition at line 1371 of file Epos2.cpp.

long CEpos2::getMaxPositionLimit ( )

function to GET the Max Position Limit

This function gets the Max Position Limit [qc]

Returns
Max Position Limit

Definition at line 1392 of file Epos2.cpp.

long CEpos2::getMinPositionLimit ( )

function to GET the Min Position Limit

This function gets the Min Position Limit [qc]

Returns
Min Position Limit

Definition at line 1381 of file Epos2.cpp.

long CEpos2::getMotorContinuousCurrentLimit ( )

function to GET Motor Continous Current Limit

This function gets Motor Continous Current Limit

Returns
Motor Continous Current Limit

Definition at line 1351 of file Epos2.cpp.

long CEpos2::getMotorOutputCurrentLimit ( )

function to GET Motor Output Current Limit

This function gets Motor Output Current Limit

Returns
Motor Output Current Limit

Definition at line 1355 of file Epos2.cpp.

void CEpos2::getMotorParameters ( long &  type,
long &  current_c_mA,
long &  current_out_mA,
char &  pole_pairs,
long &  time_ds 
)

function to GET encoder parameters

Return values
&type
&current_c_mA
&current_out_mA
&pole_pairs
&time_ds
long CEpos2::getMotorPolePairNumber ( )

function to GET Motor Pole Pair Number

This function gets Motor Pole Pair Number

Returns
Motor Pole Pair Number

Definition at line 1359 of file Epos2.cpp.

long CEpos2::getMotorType ( )

function to GET Motor type

This function gets Motor type

Returns
Motor type

Definition at line 1347 of file Epos2.cpp.

void CEpos2::getMovementInfo ( )

prints information about movement

Motor position, velocity, averaged velocity, demanded velocity, current, averaged current, demanded current.

Examples:
configtest.cpp.

Definition at line 1197 of file Epos2.cpp.

long CEpos2::getNegativeLong ( long  number)
private

function to make a unsigned long signed

This function converts an unsigned long to a signed value

Parameters
numberunsigned long number needed to convert
Returns
signed number

Definition at line 1494 of file Epos2.cpp.

long CEpos2::getOperationMode ( )

function to know which operation mode is set

This function gets the actual operation mode and returns its value as an integrer

Returns
operation mode
Todo:
veure si això fa falta

Definition at line 576 of file Epos2.cpp.

std::string CEpos2::getOpModeDescription ( long  opmode)

function to show the name of the operation mode

Parameters
opmodeintegrer returned by getOperationMode

Definition at line 590 of file Epos2.cpp.

long CEpos2::getPositionAFFGain ( )

function to get Acceleration Feed Forward Position Gain

This function gets the actual Acceleration Feed Forward Position Gain

Returns
gain

Definition at line 967 of file Epos2.cpp.

long CEpos2::getPositionDGain ( )

function to get D Position Gain

This function gets the actual D Position Gain

Returns
gain

Definition at line 946 of file Epos2.cpp.

long CEpos2::getPositionDimensionIndex ( )

function to get Position Dimension Index

This function gets Position Dimension Index

Returns
Position Dimension Index

Definition at line 1439 of file Epos2.cpp.

long CEpos2::getPositionIGain ( )

function to get I Position Gain

This function gets the actual I Position Gain

Returns
gain

Definition at line 936 of file Epos2.cpp.

long CEpos2::getPositionMarker ( int  buffer = 0)

gets the position marked by the sensor

Parameters
buffer0: captured position, 1: history 1, 2: history 2
Examples:
test_marker.cpp, and test_positions.cpp.

Definition at line 1512 of file Epos2.cpp.

long CEpos2::getPositionNotationIndex ( )

function to get Position Notation Index

This function gets Position Notation Index

Returns
Position Notation Index

Definition at line 1427 of file Epos2.cpp.

long CEpos2::getPositionPGain ( )

function to get P Position Gain

This function gets the actual P Position Gain

Returns
gain

Definition at line 926 of file Epos2.cpp.

long CEpos2::getPositionVFFGain ( )

function to get Velocity Feed Forward Position Gain

This function gets the actual Velocity Feed Forward Position Gain

Returns
gain

Definition at line 957 of file Epos2.cpp.

long CEpos2::getPositionWindow ( )

function to get Position Window

This function gets Position Window

Returns
actual output

Definition at line 1411 of file Epos2.cpp.

long CEpos2::getPositionWindowTime ( )

function to get Position Window Time

This function gets Position Window Time

Returns
actual output

Definition at line 1415 of file Epos2.cpp.

long CEpos2::getProfileAcceleration ( void  )

function to GET the Acceleration in profile

This function gets the Acceleration in profile [rev/min/s]

Returns
acceleration

Definition at line 1049 of file Epos2.cpp.

void CEpos2::getProfileData ( long &  vel,
long &  maxvel,
long &  acc,
long &  dec,
long &  qsdec,
long &  maxacc,
long &  type 
)

function to GET all data of the velocity profile

This function gets all data and stores it in the output parameters defined.

Return values
&velProfile Velocity
&maxvelProfile Max Velocity
&accProfile Acceleration
&decProfile Deceleration
&qsdecProfile Quick Stop Deceleration
&maxaccProfile Max Acceleration
&typeProfile Type
Examples:
configtest.cpp, and test_epos2.cpp.

Definition at line 1099 of file Epos2.cpp.

long CEpos2::getProfileDeceleration ( void  )

function to GET the Deceleration in profile

This function gets the Deceleration in profile [rev/min/s]

Returns
Deceleration

Definition at line 1059 of file Epos2.cpp.

long CEpos2::getProfileMaxVelocity ( void  )

function to GET the Max Velocity allowed in Profile

This function gets the Max Velocity allowed in Profile [rev/min]

Returns
Max Velocity

Definition at line 1039 of file Epos2.cpp.

long CEpos2::getProfileQuickStopDecel ( void  )

function to GET the Quick Stop Deceleration in profile

This function gets the Quick Stop Deceleration in profile [rev/min/s]

Returns
deceleration

Definition at line 1069 of file Epos2.cpp.

long CEpos2::getProfileType ( void  )

function to GET the type in profile

This function gets the type in profile trapezoidal if 0, sinusoidal otherwise

Returns
Max Position Limit

Definition at line 1079 of file Epos2.cpp.

long CEpos2::getProfileVelocity ( void  )

function to GET the velocity of the Velocity Profile

This function gets the velocity of the velocity profile used in Profile Position and Profile Velocity [rev/min]

Returns
Profile Velocity

Definition at line 1029 of file Epos2.cpp.

long CEpos2::getRS232Baudrate ( )

function to GET the RS232 Baudrate

This function gets the RS232 Baudrate of the controller

Returns
RS232 Baudrate

Definition at line 1464 of file Epos2.cpp.

long CEpos2::getRS232FrameTimeout ( )

function to GET the RS232 Frame Timeout

This function gets the RS232 Frame Timeout of the controller

Returns
RS232 Frame Timeout [ms]

Definition at line 1474 of file Epos2.cpp.

long CEpos2::getState ( )

function to get current controller's state

EPOS2 State Machine with libEPOS2 functions See EPOS2 state machine

Returns
arbitrary state number of STATES

Definition at line 397 of file Epos2.cpp.

long CEpos2::getTargetCurrent ( )

[OPMODE=current] function to GET the target current

Todo:
CURRENT MODE FUNCTIONS

This function gets the target current of current operation mode

Returns
Target current

Definition at line 858 of file Epos2.cpp.

long CEpos2::getTargetProfilePosition ( )

function to GET the target position

This function gets the target position of profile position operation mode

Returns
Target position
Examples:
configtest.cpp.

Definition at line 817 of file Epos2.cpp.

long CEpos2::getTargetProfileVelocity ( )

[OPMODE=profile_velocity] function to get the velocity

Precondition
Operation Mode = profile_velocity
Returns
Target Velocity of the profile
Examples:
configtest.cpp.

Definition at line 778 of file Epos2.cpp.

long CEpos2::getTargetVelocity ( )

function to GET the target velocity This function gets the target velocity of velocity operation mode

Returns
Target Velocity
Examples:
configtest.cpp.

Definition at line 742 of file Epos2.cpp.

long CEpos2::getThermalTimeCtWinding ( )

function to GET Motor Thermal Time Constant Winding

This function gets Motor Thermal Time Constant Winding

Returns
Motor Thermal Time Constant Winding

Definition at line 1363 of file Epos2.cpp.

long CEpos2::getUSBFrameTimeout ( )

function to GET the USB Frame Timeout

This function gets the USB Frame Timeout of the controller

Returns
USB Frame Timeout [ms]

Definition at line 1484 of file Epos2.cpp.

long CEpos2::getVelocityDimensionIndex ( )

function to get Velocity Dimension Index

This function gets Velocity Dimension Index

Returns
Velocity Dimension Index

Definition at line 1443 of file Epos2.cpp.

long CEpos2::getVelocityIGain ( )

function to get I Velocity Gain

This function gets the actual I Velocity Gain

Returns
gain

Definition at line 904 of file Epos2.cpp.

long CEpos2::getVelocityNotationIndex ( )

function to get Velocity Notation Index

This function gets Velocity Notation Index

Returns
Velocity Notation Index

Definition at line 1431 of file Epos2.cpp.

long CEpos2::getVelocityPGain ( )

function to get P Velocity Gain

This function gets the actual P Velocity Gain

Returns
gain

Definition at line 894 of file Epos2.cpp.

long CEpos2::getVelocitySetPointFactorPGain ( )

function to GET Speed Regulator Set Point Factor P Velocity Gain

This function gets the actual Speed Regulator Set Point Factor P Velocity Gain

Returns
gain

Definition at line 914 of file Epos2.cpp.

long CEpos2::getVelocityWindow ( )

function to get Velocity Window

This function gets Velocity Window

Returns
Velocity Window

Definition at line 1419 of file Epos2.cpp.

long CEpos2::getVelocityWindowTime ( )

function to get Velocity Window Time

This function gets Velocity Window Time

Returns
actual output

Definition at line 1423 of file Epos2.cpp.

bool CEpos2::getVerbose ( )

Definition at line 82 of file Epos2.cpp.

void CEpos2::init ( )

Connects hardware.

Examples:
configtest.cpp, test_epos2.cpp, test_homing.cpp, test_like_h3d.cpp, test_marker.cpp, and test_positions.cpp.

Definition at line 49 of file Epos2.cpp.

bool CEpos2::isTargetReached ( )

function to know if the motor has reached the target position or velocity

Precondition
Operation Mode = profile_position or profile_velocity
Returns
A boolean, target reached
Examples:
configtest.cpp.

Definition at line 720 of file Epos2.cpp.

void CEpos2::openDevice ( )
private

open EPOS2 device using CFTDI

It finds and configures the FTDI communication.

Definition at line 105 of file Epos2.cpp.

void CEpos2::p ( const char *  text)
private

function to make a unsigned long signed

This function converts an unsigned long to a signed value

Parameters
numberunsigned long number needed to convert
Returns
signed number

Definition at line 74 of file Epos2.cpp.

void CEpos2::p ( const std::stringstream &  text)
private

Definition at line 66 of file Epos2.cpp.

void CEpos2::printControlParameters ( long  cp,
long  ci,
long  vp,
long  vi,
long  vspf,
long  pp,
long  pi,
long  pd,
long  pv,
long  pa 
)

function to show all control parameters

Prints all control parameters got before with getControlParameters in cout

Parameters
cpCurrent Proportional
ciCurrent Integral
vpVelocity Proportional
viVelocity Integral
vspfVelocity Set Point Factor P Gain
ppPostition Proportional
piPosition Integral
pdPosition Derivative
pvPosition Velocity Feed Forward Factor
paPosition Acceleration Feed Forward Factor

Definition at line 1015 of file Epos2.cpp.

void CEpos2::quickStop ( )

function to reach switch_on state

Transitions: 7,10,11 EPOS2 State Machine with libEPOS2 functions See EPOS2 state machine

Definition at line 541 of file Epos2.cpp.

long CEpos2::readCurrent ( )

function to read motor current

This function reads the actual current of the motor [mA]

Returns
actual current
Examples:
configtest.cpp.

Definition at line 1150 of file Epos2.cpp.

long CEpos2::readCurrentAveraged ( )

function to read motor averaged current

The current actual value averaged [mA] represents the current actual value filtered by 1st order digital lowpass filter with a cut-off frequency of 50 Hz.This function reads the current of the motor averaged [mA]

Returns
current averaged
Examples:
configtest.cpp.

Definition at line 1156 of file Epos2.cpp.

long CEpos2::readCurrentDemanded ( )

function to read current demanded

The «Current Demand Value» is the set value [mA] for the current controller

[mA]

Returns
demanded current
Examples:
configtest.cpp.

Definition at line 1162 of file Epos2.cpp.

long CEpos2::readEncoderCounter ( )

function to read the Encoder Counter

This function reads the internal counter register of the encoder multiplied by Polarity [qc]

Returns
Encoder Counter
Examples:
configtest.cpp.

Definition at line 1177 of file Epos2.cpp.

long CEpos2::readEncoderCounterAtIndexPulse ( )

function to read the Encoder Counter at index pulse

This function reads the encoder counter reached at last detected encoder index pulse. [qc]

Returns
Encoder Counter at index pulse
Examples:
configtest.cpp.

Definition at line 1182 of file Epos2.cpp.

char CEpos2::readError ( )

function to read an Error information

This function reads the information of an error

Returns
StatusWord
Examples:
configtest.cpp.

Definition at line 1226 of file Epos2.cpp.

void CEpos2::readErrorHistory ( long *  error[5])

function to read last 5 errors

This function reads the information of last five errors in EPOS

Returns
Errors
Examples:
configtest.cpp.

Definition at line 1258 of file Epos2.cpp.

long CEpos2::readFollowingError ( )

function to read the Following Error

This function reads the actual Following Error [qc]

Returns
Following Error
Examples:
configtest.cpp.

Definition at line 1192 of file Epos2.cpp.

long CEpos2::readHallsensorPattern ( )

function to read the Hall Sensor Pattern

This function reads the actual state of the three hall sensors as a pattern. bit 0: hallsensor 1 bit 1: hallsensor 2 bit 2: hallsensor 3

Returns
Hallsensor Pattern
Examples:
configtest.cpp.

Definition at line 1187 of file Epos2.cpp.

int32_t CEpos2::readObject ( int16_t  index,
int8_t  subindex 
)
private

function to read an object from the EPOS2

This function sends a read object request using CFTDI.

Parameters
indexthe hexadecimal index of the object you want to read
subindexhexadecimal value of the object (usually 0x00)
Returns
the value in the object as a long

Definition at line 123 of file Epos2.cpp.

int32_t CEpos2::readPosition ( )

function to read motor position

This function reads the actual current of the motor. [qc] To get load position just do: load_pos[º] = motor_pos[qc] / ( 4 * encoder_pulses [lines/rev] * reduction )

Returns
actual current
Examples:
configtest.cpp, test_epos2.cpp, and test_like_h3d.cpp.

Definition at line 1167 of file Epos2.cpp.

long CEpos2::readStatusWord ( )

function to read EPOS2 StatusWord

This function reads the StatusWord. It doesn't give more information than just the returned StatusWord

Returns
StatusWord
Examples:
configtest.cpp.

Definition at line 1172 of file Epos2.cpp.

long CEpos2::readVelocity ( )

function to read motor average velocity

This function reads the actual velocity of the motor [rev/min] -2147483648..2147483647

Returns
averaged velocity
Examples:
configtest.cpp.

Definition at line 1130 of file Epos2.cpp.

long CEpos2::readVelocityActual ( )

function to read velocity sensor actual

Description The velocity actual value is coupled to the velocity used as input to velocity controller [Velocity units]. Remarks The resolution of the short time velocity measurement (Velocity actual value, Velocity sensor actual value) is dependent on the encoder pulse number (Sensor Configuration) and the velocity measurement method (Miscellaneous Configuration bit 3). To improve the short time velocity measurement resolution set the Miscellaneous Configuration bit 3 to 1 or use an encoder with higher resolution. For example the short time velocity resolution with a 500-pulse encoder and Miscellaneous Configuration Bit 3 = 0 is: 1 quadcount / ms = 60’000 / (4 * 500) = 30 rpm.

Returns
actual velocity
Examples:
configtest.cpp.

Definition at line 1145 of file Epos2.cpp.

long CEpos2::readVelocityDemand ( )

function to read velocity demand

Velocity demand value is generated by profile generator and is the set value for the velocity controller

Returns
demanded velocity
Examples:
configtest.cpp.

Definition at line 1140 of file Epos2.cpp.

long CEpos2::readVelocitySensorActual ( )

function to read velocity sensor actual

Description The velocity sensor actual value is given in quadcounts per second [inc/s]. Remarks The resolution of the short time velocity measurement (Velocity actual value, Velocity sensor actual value) is dependent on the encoder pulse number (Sensor Configuration) and the velocity measurement method (Miscellaneous Configuration bit 3). To improve the short time velocity measurement resolution set the Miscellaneous Configuration bit 3 to 1 or use an encoder with higher resolution. For example the short time velocity resolution with a 500-pulse encoder and Miscellaneous Configuration Bit 3 = 0 is: 1 quadcount / ms = 60’000 / (4 * 500) = 30 rpm.

[qc/s]

Returns
sensor velocity
Examples:
configtest.cpp.

Definition at line 1135 of file Epos2.cpp.

long CEpos2::readVersionHardware ( )

function to read the hardware version

This function reads the hardware version.

Returns
Hardware Version
Examples:
configtest.cpp.

Definition at line 1308 of file Epos2.cpp.

long CEpos2::readVersionSoftware ( )

function to read the software version

This function reads the software version, it can be useful to know if EPOS2 has the last firmware.

Returns
Software Version
Examples:
configtest.cpp.

Definition at line 1303 of file Epos2.cpp.

void CEpos2::receiveFrame ( uint16_t *  ans_frame)
private

function receive a frame from EPOS2

It uses CFTDI events in order to get complete frames of data from EPOS2. While frame is being received it calculates its length using the fourth piece of data and checks if data pieces have been stuffed for character 0x90, If there are, frame length is changed. Also It converts the 8 bit received frame to 16 bit frame.

Parameters
framedata frame which will be saved from EPOS2

Definition at line 229 of file Epos2.cpp.

void CEpos2::restoreDefaultParameters ( )

function to restore default parameters of EPOS2.

This function restores all default parameters of EPOS2.

Warning
It removes its actual values! (ALL)
Examples:
configtest.cpp.

Definition at line 1458 of file Epos2.cpp.

void CEpos2::saveParameters ( )

function to save all parameters in EEPROM

This function save all actual parameters to EEPROM of EPOS2. Its necessary if you do changes you want to save such as new controller parameters or profiles.

Examples:
configtest.cpp.

Definition at line 1452 of file Epos2.cpp.

std::string CEpos2::searchErrorDescription ( long  error_code)

given an error code it returns its description

Returns
Errors

Definition at line 1275 of file Epos2.cpp.

void CEpos2::sendFrame ( int16_t *  frame)
private

function send a frame to EPOS2

It transforms the 16 bit frame to 8 bit and does data stuffing for character 0x90.

Parameters
framedata frame which will be sent to EPOS2

Definition at line 186 of file Epos2.cpp.

void CEpos2::setAccelerationDimensionIndex ( long  Dimension)

function to set Acceleration Dimension Index

This function sets Acceleration Dimension Index

Parameters
DimensionDimension and Notation Factor Tables

Definition at line 1449 of file Epos2.cpp.

void CEpos2::setAccelerationNotationIndex ( long  notation)

function to set Acceleration Notation Index

This function sets Acceleration Notation Index

Parameters
notationDimension and Notation Factor Tables

Definition at line 1437 of file Epos2.cpp.

void CEpos2::setAnalogOutput1 ( long  voltage_mV)

function to set analog output 1

This function sets the analog output1 voltage. ONLY in 50/5 Controller!! Resolution 2.40 mV, Bandwith 20 kHz [mV] 0..10000

analog_output_connector_hardware_reference_pg29.png
Parameters
voltage_mV

Definition at line 1508 of file Epos2.cpp.

void CEpos2::setControlParameters ( long  cp,
long  ci,
long  vp,
long  vi,
long  vspf,
long  pp,
long  pi,
long  pd,
long  pv,
long  pa 
)

function to set all control parameters

Sets all control parameters

Parameters
cpCurrent Proportional
ciCurrent Integral
vpVelocity Proportional
viVelocity Integral
vspfVelocity Set Point Factor P Gain
ppPostition Proportional
piPosition Integral
pdPosition Derivative
pvPosition Velocity Feed Forward Factor
paPosition Acceleration Feed Forward Factor
Examples:
configtest.cpp.

Definition at line 996 of file Epos2.cpp.

void CEpos2::setCurrentIGain ( long  gain)

function to set I Current Gain

This function sets Current Gain

Parameters
gain(must be between 0 and 32767)

Definition at line 887 of file Epos2.cpp.

void CEpos2::setCurrentPGain ( long  gain)

function to set P Current Gain

This function sets Current Gain

Parameters
gain(must be between 0 and 32767)

Definition at line 877 of file Epos2.cpp.

void CEpos2::setEncoderParameters ( long  pulses,
long  type,
long  polarity 
)

function to SET encoder parameters

Parameters
pulses
type
polarity

Definition at line 1342 of file Epos2.cpp.

void CEpos2::setEncoderPolarity ( long  polarity)

function to SET the Encoder polarity

This function sets the Encoder polarity bit 0: Incremental Encoder (0:CCW, 1:CW (encoder mounted on motor shaft) bit 1: Hall s (0:normal, 1:inverted) bit 2: SSI Encoder (0: CCW, 1:inverted)

DISABLE STATE only

Parameters
polarity

Definition at line 1336 of file Epos2.cpp.

void CEpos2::setEncoderPulseNumber ( long  pulses)

function to SET the Encoder Pulses

This function sets the Encoder pulses 16...2500000 DISABLE STATE only

Parameters
pulses

Definition at line 1322 of file Epos2.cpp.

void CEpos2::setEncoderType ( long  type)

function to SET the Encoder type

This function sets the Encoder type 0=unknown,1=incremental+index,2=incremental,3=Hall DISABLE STATE only

Parameters
type

Definition at line 1330 of file Epos2.cpp.

void CEpos2::setHome ( )

function to set a Home position with user interaction

This function sets a new home position with user interaction. User has to follow instructions given when the function is called. It disables power, then user has to rotate the load and then the function reads the actual position and set there the new home

   disable -> user rotate -> readPosition -> setHomePosition
Examples:
configtest.cpp.

Definition at line 1636 of file Epos2.cpp.

void CEpos2::setHomePosition ( long  home_position_qc)

function to set a Home position

This function sets a home position.

Parameters
home_position_qcposition to set home

Definition at line 1627 of file Epos2.cpp.

void CEpos2::setHoming ( int  home_method = 11,
int  speed_pos = 100,
int  speed_zero = 100,
int  acc = 1000,
int  digitalIN = 2 
)

Sets the configuration of a homing operation.

It can use a sensor to reach the home, this sensor can be set as positive (18,2), negative(17,1) or home(27,23,11,7) switch. If the system doesn't have a switch, setting actual position as home (35) and Index methods (34,33) can be used.

Parameters
home_method
# Description
35 Set Actual Position as home position
34 Index Negative / Positive Speed
33 Index Negative / Positive Speed
27 Home Switch Negative Speed
23 Home Switch Positive Speed
18 Positive Limit Switch
17 Negative Limit Switch
11 Home Switch Negative Speed & Index
7 Home Switch Positive Speed & Index
2 Positive Limit Switch & Index
1 Negative Limit Switch & Index
0 No homing operation required
-1 Current Threshold Positive Speed & Index
-2 Current Threshold Negative Speed & Index
-3 Current Threshold Positive Speed
-4 Current Threshold Negative Speed
speed_posSpeed for first positioning
speed_zeroSpeed for find home near 0
accAcceleration
digitalINThe pin which has the home switch property
Examples:
test_homing.cpp.

Definition at line 1562 of file Epos2.cpp.

void CEpos2::setMaxAcceleration ( long  max_acceleration)

function to SET Max Acceleration

This function sets Max Acceleration [rev/min/s]

Parameters
max_acceleration

Definition at line 1094 of file Epos2.cpp.

void CEpos2::setMaxFollowingError ( long  follerror)

function to SET the Max Following Error

This function sets the Max following error [qc] 0..4294967295

Parameters
follerror

Definition at line 1376 of file Epos2.cpp.

void CEpos2::setMaxPositionLimit ( long  limit)

function to SET the Max Position Limit

This function sets the Max Position Limit [qc] -2147483648..2147483647

Parameters
limit

Definition at line 1397 of file Epos2.cpp.

void CEpos2::setMinPositionLimit ( long  limit)

function to SET the Min Position Limit

This function sets the Min Position Limit [qc] -2147483648..2147483647

Parameters
limit

Definition at line 1386 of file Epos2.cpp.

void CEpos2::setMotorContinuousCurrentLimit ( long  current_mA)

function to SET Motor Continous Current Limit

This function sets Motor Continous Current Limit [mA]

Parameters
current_mA[mA]

Definition at line 1353 of file Epos2.cpp.

void CEpos2::setMotorOutputCurrentLimit ( long  current_mA)

function to SET Motor Output Current Limit

This function sets Motor Output Current Limit Usually 2·Continous current limit [mA]

Parameters
current_mA[mA]

Definition at line 1357 of file Epos2.cpp.

void CEpos2::setMotorParameters ( long  type,
long  current_c_mA,
long  current_out_mA,
char  pole_pairs,
long  time_ds 
)

function to SET motor parameters

Parameters
type
current_c_mA
current_out_mA
pole_pairs
time_ds
void CEpos2::setMotorPolePairNumber ( char  pole_pairs)

function to SET Motor Pole Pair Number

This function sets Motor Pole Pair Number number of poles / 2

Disable State

Parameters
pole_pairs

Definition at line 1361 of file Epos2.cpp.

void CEpos2::setMotorType ( long  type)

function to SET Motor type

This function sets Motor type 1: brushed DC motor 10: EC motor sinus commutated 11: EC motor block commutated

DISABLE STATE only

Parameters
type

Definition at line 1349 of file Epos2.cpp.

void CEpos2::setOperationMode ( long  opmode)

function to set the operation mode

Parameters
opmodedesired operation mode (one of epos_opmodes)
Examples:
configtest.cpp, test_epos2.cpp, test_like_h3d.cpp, and test_positions.cpp.

Definition at line 624 of file Epos2.cpp.

void CEpos2::setPositionAFFGain ( long  gain)

function to set Acceleration Feed Forward Position Gain

This function sets the actual Acceleration Feed Forward Position Gain

Parameters
gain(must be between 0 and 65535)

Definition at line 972 of file Epos2.cpp.

void CEpos2::setPositionDGain ( long  gain)

function to set D Position Gain

This function sets the actual D Position Gain

Parameters
gain(must be between 0 and 32767)

Definition at line 952 of file Epos2.cpp.

void CEpos2::setPositionDimensionIndex ( long  Dimension)

function to set Position Dimension Index

This function sets Position Dimension Index

Parameters
DimensionDimension and Notation Factor Tables

Definition at line 1441 of file Epos2.cpp.

void CEpos2::setPositionIGain ( long  gain)

function to set I Position Gain

This function sets the actual I Position Gain

Parameters
gain(must be between 0 and 32767)

Definition at line 941 of file Epos2.cpp.

void CEpos2::setPositionMarker ( char  polarity = 0,
char  edge_type = 0,
char  mode = 0,
char  digitalIN = 2 
)

Sets the configuration of a marker position.

Parameters
digitalINThe pin which has the Marker position switch property
polarity0: true on high, 1: true on low
edge_type0 : rising, 1: falling, 2: both
mode0: continuous 1: single 2: multiple
Examples:
test_marker.cpp, and test_positions.cpp.

Definition at line 1530 of file Epos2.cpp.

void CEpos2::setPositionNotationIndex ( long  notation)

function to set Position Notation Index

This function sets Position Notation Index

Parameters
notationDimension and Notation Factor Tables

Definition at line 1429 of file Epos2.cpp.

void CEpos2::setPositionPGain ( long  gain)

function to set P Position Gain

This function sets the actual P Position Gain

Parameters
gain(must be between 0 and 32767)

Definition at line 931 of file Epos2.cpp.

void CEpos2::setPositionVFFGain ( long  gain)

function to set Velocity Feed Forward Position Gain

This function sets the actual Velocity Feed Forward Position Gain

Parameters
gain(must be between 0 and 65535)

Definition at line 962 of file Epos2.cpp.

void CEpos2::setPositionWindow ( long  window_qc)

function to set Position Window

This function sets Position Window Disable: 4’294’967’295 [qc] 0..2’147’483’647

Parameters
window_qc[qc]

Definition at line 1413 of file Epos2.cpp.

void CEpos2::setPositionWindowTime ( long  time_ms)

function to set Position Window Time

This function sets Position Window Time [ms] 0..65535

Parameters
time_ms[ms]

Definition at line 1417 of file Epos2.cpp.

void CEpos2::setProfileAcceleration ( long  acceleration)

function to SET the Acceleration in profile

This function sets the Acceleration in profile [rev/min/s]

Parameters
acceleration

Definition at line 1054 of file Epos2.cpp.

void CEpos2::setProfileData ( long  vel,
long  maxvel,
long  acc,
long  dec,
long  qsdec,
long  maxacc,
long  type 
)

function to SET all data of the velocity profile

This function sets all data of the velocity profile.

Parameters
velProfile Velocity
maxvelProfile Max Velocity
accProfile Acceleration
decProfile Deceleration
qsdecProfile Quick Stop Deceleration
maxaccProfile Mac Acceleration
typeProfile Type
Examples:
configtest.cpp.

Definition at line 1111 of file Epos2.cpp.

void CEpos2::setProfileDeceleration ( long  deceleration)

function to SET the Deceleration in profile

This function sets the Max Deceleration in profile [rev/min/s]

Parameters
deceleration

Definition at line 1064 of file Epos2.cpp.

void CEpos2::setProfileMaxVelocity ( long  velocity)

function to SET the Max Velocity allowed in Profile

This function sets the Max Velocity allowed in Profile [rev/min]

Parameters
velocity

Definition at line 1044 of file Epos2.cpp.

void CEpos2::setProfileQuickStopDecel ( long  deceleration)

function to SET the Quick Stop Deceleration in profile

This function sets the Quick Stop Deceleration in profile [rev/min/s]

Parameters
deceleration

Definition at line 1074 of file Epos2.cpp.

void CEpos2::setProfileType ( long  type)

function to SET the type in profile

This function sets the type in profile (0=Trapezoidal or 1=Sinusoidal)

Parameters
type

Definition at line 1084 of file Epos2.cpp.

void CEpos2::setProfileVelocity ( long  velocity)

function to SET the velocity of the Velocity Profile

This function sets the velocity of the velocity profile used in Profile Position and Profile Velocity [rev/min]

Parameters
velocity

Definition at line 1034 of file Epos2.cpp.

void CEpos2::setRS232Baudrate ( long  baudrate)

function to SET the RS232 Baudrate

This function sets the RS232 Baudrate (Firmware 14.36) 0: 9.6 kBaud 1: 14.4 kBaud 2: 19.2 kBaud 3: 38.4 kBaud 4: 57.6 kBaud 5: 115.2 kBaud

It needs to saveParameters and then restart EPOS2

Parameters
baudratedesired following the table

Definition at line 1469 of file Epos2.cpp.

void CEpos2::setRS232FrameTimeout ( long  timeout)

function to SET the RS232 Frame Timeout

This function sets the RS232 Frame Timeout [ms] (500 by default)

Parameters
timeoutin [ms]

Definition at line 1479 of file Epos2.cpp.

void CEpos2::setTargetCurrent ( long  current)

[OPMODE=current] function to SET the target current

This function sets the target current of current operation mode

Parameters
currentTarget current

Definition at line 860 of file Epos2.cpp.

void CEpos2::setTargetProfilePosition ( long  position)

function to SET the target position

This function sets the target position of profile position operation mode

Parameters
positionTarget position
Examples:
configtest.cpp, and test_epos2.cpp.

Definition at line 825 of file Epos2.cpp.

void CEpos2::setTargetProfileVelocity ( long  velocity)

[OPMODE=profile_velocity] function to set the velocity

Precondition
Operation Mode = profile_velocity
Parameters
velocitydesired velocity
Examples:
configtest.cpp, and test_epos2.cpp.

Definition at line 787 of file Epos2.cpp.

void CEpos2::setTargetVelocity ( long  velocity)

function to SET the target velocity

This function sets the target velocity of velocity operation mode

Parameters
velocityTarget Velocity
Examples:
configtest.cpp, test_epos2.cpp, test_like_h3d.cpp, and test_positions.cpp.

Definition at line 750 of file Epos2.cpp.

void CEpos2::setThermalTimeCtWinding ( long  time_ds)

function to SET Motor Thermal Time Constant Winding

This function sets Motor Thermal Time Constant Winding [ds] = [s*10]

Parameters
time_ds

Definition at line 1365 of file Epos2.cpp.

void CEpos2::setUSBFrameTimeout ( long  timeout)

function to SET the USB Frame Timeout

This function sets the USB Frame Timeout [ms] (500 by default)

Parameters
timeoutin [ms]

Definition at line 1489 of file Epos2.cpp.

void CEpos2::setVelocityDimensionIndex ( long  Dimension)

function to set Velocity Dimension Index

This function sets Velocity Dimension Index

Parameters
DimensionDimension and Notation Factor Tables

Definition at line 1445 of file Epos2.cpp.

void CEpos2::setVelocityIGain ( long  gain)

function to set I Velocity Gain

This function sets Velocity Gain

Parameters
gain(must be between 0 and 32767)

Definition at line 909 of file Epos2.cpp.

void CEpos2::setVelocityNotationIndex ( long  notation)

function to set Velocity Notation Index

This function sets Velocity Notation Index

Parameters
notationDimension and Notation Factor Tables

Definition at line 1433 of file Epos2.cpp.

void CEpos2::setVelocityPGain ( long  gain)

function to set P Velocity Gain

This function sets P Velocity Gain

Parameters
gain(must be between 0 and 32767)

Definition at line 899 of file Epos2.cpp.

void CEpos2::setVelocitySetPointFactorPGain ( long  gain)

function to SET Speed Regulator Set Point Factor P Velocity Gain

This function sets Speed Regulator Set Point Factor P Velocity Gain

0..32767

Parameters
gain

Definition at line 919 of file Epos2.cpp.

void CEpos2::setVelocityWindow ( long  window_rm)

function to set Velocity Window

This function sets Velocity Window [qc] 0..4’294’967’295

Parameters
window_rm[rev/min]

Definition at line 1421 of file Epos2.cpp.

void CEpos2::setVelocityWindowTime ( long  time_ms)

function to set Velocity Window Time

This function sets Velocity Window Time [ms] 0..65535

Parameters
time_ms[ms]

Definition at line 1425 of file Epos2.cpp.

void CEpos2::setVerbose ( bool  verbose)
Examples:
configtest.cpp, test_epos2.cpp, test_homing.cpp, and test_marker.cpp.

Definition at line 90 of file Epos2.cpp.

void CEpos2::shutdown ( )

function to reach ready_to_switch_on state

Transitions: 2,6 EPOS2 State Machine with libEPOS2 functions See EPOS2 state machine

Definition at line 517 of file Epos2.cpp.

void CEpos2::startCurrent ( )

[OPMODE=current] function to move the motor in current mode

This function makes move the motor if current mode is the actual operation mode

Precondition
Operation Mode = current

Definition at line 862 of file Epos2.cpp.

void CEpos2::startProfilePosition ( epos_posmodes  mode,
bool  blocking = true,
bool  wait = true,
bool  new_point = true 
)

function to move the motor to a position in profile position mode

This function makes move the motor if profile position mode is the actual operation mode epos_posmodes: halt:0, absolut:1, relative:2

Precondition
Operation Mode = profile_position
Parameters
modeepos_posmodes
blockingIf it block the program or if it leave the program manage position reached
waitIf it has to wait current movement to finish or just start the new one
new_pointAssume Target position (seems that it doesn't do anything)
Examples:
configtest.cpp, and test_epos2.cpp.

Definition at line 831 of file Epos2.cpp.

void CEpos2::startProfileVelocity ( )

[OPMODE=profile_velocity] function to move the motor in a velocity

Precondition
Operation Mode = profile_velocity
Examples:
configtest.cpp, and test_epos2.cpp.

Definition at line 795 of file Epos2.cpp.

void CEpos2::startVelocity ( )

function to move the motor in Velocity mode

This function makes move the motor if velocity mode is the actual operation mode

Precondition
Operation Mode = velocity
Examples:
configtest.cpp, test_epos2.cpp, test_like_h3d.cpp, and test_positions.cpp.

Definition at line 758 of file Epos2.cpp.

void CEpos2::stopCurrent ( )

[OPMODE=current] function to stop the motor in current mode

This function stops the motor if current mode is the actual operation mode

Precondition
Operation Mode = current

Definition at line 864 of file Epos2.cpp.

void CEpos2::stopHoming ( )

stops a homing operation

Definition at line 1587 of file Epos2.cpp.

void CEpos2::stopProfileVelocity ( )

[OPMODE=profile_velocity] function to stop the motor

Precondition
Operation Mode = profile_velocity
Examples:
configtest.cpp, and test_epos2.cpp.

Definition at line 805 of file Epos2.cpp.

void CEpos2::stopVelocity ( )

function to stop the motor in velocity mode

This function stops the motor if velocity mode is the actual operation mode

Precondition
Operation Mode = velocity
Examples:
configtest.cpp, test_epos2.cpp, test_like_h3d.cpp, and test_positions.cpp.

Definition at line 766 of file Epos2.cpp.

void CEpos2::switchOn ( )

function to reach switch_on state

Transitions: 3 EPOS2 State Machine with libEPOS2 functions See EPOS2 state machine

Definition at line 525 of file Epos2.cpp.

static void* CEpos2::threadTargetReached ( void *  param)
static

Thread listens to target reached.

Parameters
param
void CEpos2::waitPositionMarker ( )

wait for marker position reached

Parameters
param
Examples:
test_marker.cpp.

Definition at line 1546 of file Epos2.cpp.

int32_t CEpos2::writeObject ( int16_t  index,
int8_t  subindex,
int32_t  data 
)
private

function to write an object to the EPOS2

This function sends a write object request using CFTDI.

Parameters
indexthe hexadecimal index of the object you want to read
subindexhexadecimal value of the object (usually 0x00)
datainformation to send
Returns
returned value by write

Definition at line 158 of file Epos2.cpp.

Member Data Documentation

const int CEpos2::error_codes
static

error integer codes

Definition at line 1151 of file Epos2.h.

const std::string CEpos2::error_descriptions
static

error descriptions

Definition at line 1154 of file Epos2.h.

const std::string CEpos2::error_names
static
Initial value:
= {
"Generic Error",
"Current Error",
"Voltage Error",
"Temperature Error",
"Communication Error",
"Device profile specific",
"Motion Error"
}

Strings of generic error descriptions.

Definition at line 1148 of file Epos2.h.

Ftdi::Context CEpos2::ftdi
staticprivate

a reference to the FTDI USB device

This attribute points to the communication device used to send and receive data to and from the EPOS2. The communication device is cretaed inside the object at initialization time using the CFTDIServer and the description or serial number of the desired platform via the connect() function.

It is not possible to send or receive data to or from the epos2 until the driver is not connected to the hardware platform. Any attempt to do so will result in an exception being thrown.

Definition at line 80 of file Epos2.h.

bool CEpos2::ftdi_initialized = false
staticprivate

Definition at line 81 of file Epos2.h.

int8_t CEpos2::node_id
private

Definition at line 65 of file Epos2.h.

bool CEpos2::verbose
private

Definition at line 165 of file Epos2.h.


The documentation for this class was generated from the following files:


epos2_motor_controller
Author(s): Martí Morta Garriga , Jochen Sprickerhof
autogenerated on Mon Jul 22 2019 03:19:01