104 int32_t
readObject(int16_t index, int8_t subindex);
116 int writeObject(int16_t index, int8_t subindex, int32_t data);
175 void p(
const char *text);
178 void p(
const std::stringstream& text);
185 CEpos2(int8_t nodeId = 0x00);
739 void getControlParameters(
long &cp,
long &ci,
long &vp,
long &vi,
long &vspf,
long &pp,
long &pi,
long &pd,
long &pv,
long &pa);
757 void setControlParameters(
long cp,
long ci,
long vp,
long vi,
long vspf,
long pp,
long pi,
long pd,
long pv,
long pa);
775 void printControlParameters(
long cp,
long ci,
long vp,
long vi,
long vspf,
long pp,
long pi,
long pd,
long pv,
long pa);
944 void getProfileData (
long &vel,
long &maxvel,
long &acc,
long &dec,
long &qsdec,
long &maxacc,
long &type);
960 void setProfileData (
long vel,
long maxvel,
long acc,
long dec,
long qsdec,
long maxacc,
long type);
1385 void getMotorParameters(
long &type,
long ¤t_c_mA,
long ¤t_out_mA,
char &pole_pairs,
long &time_ds);
1395 void setMotorParameters(
long type,
long current_c_mA,
long current_out_mA,
char pole_pairs,
long time_ds);
1801 char mode = 0,
char digitalIN = 2);
1843 void setHoming(
int home_method = 11,
int speed_pos = 100,
1844 int speed_zero = 100,
int acc = 1000,
int digitalIN = 2);
1908 :
std::runtime_error (error_description) {}
1915 :
std::runtime_error (error_description) {}
1922 :
std::runtime_error (error_description) {}
long getState()
function to get current controller's state
void setCurrentPGain(long gain)
function to set P Current Gain
void setVelocityIGain(long gain)
function to set I Velocity Gain
long getPositionAFFGain()
function to get Acceleration Feed Forward Position Gain
long readStatusWord()
function to read EPOS2 StatusWord
long getPositionWindowTime()
function to get Position Window Time
long getThermalTimeCtWinding()
function to GET Motor Thermal Time Constant Winding
char readError()
function to read an Error information
void disableOperation()
function to reach switch_on and disables power on motor
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
void setHomePosition(long home_position_qc)
function to set a Home position
long readCurrentDemanded()
function to read current demanded
long getMaxAcceleration(void)
function to GET Max Acceleration
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
void waitPositionMarker()
wait for marker position reached
void enableMotor(long opmode)
function to facititate transitions from switched on to operation enabled
void setPositionMarker(char polarity=0, char edge_type=0, char mode=0, char digitalIN=2)
Sets the configuration of a marker position.
void setMinPositionLimit(long limit)
function to SET the Min Position Limit
long readVelocitySensorActual()
function to read velocity sensor actual
void setPositionWindow(long window_qc)
function to set Position Window
void setPositionWindowTime(long time_ms)
function to set Position Window Time
int getDigInExecutionMask()
Gives Digital Inputs Execution Mask.
long getMaxFollowingError()
function to GET the Max Following Error
void setVelocitySetPointFactorPGain(long gain)
function to SET Speed Regulator Set Point Factor P Velocity Gain
void setRS232Baudrate(long baudrate)
function to SET the RS232 Baudrate
void getEncoderParameters(long &pulses, long &type, long &polarity)
function to GET encoder parameters
long getUSBFrameTimeout()
function to GET the USB Frame Timeout
long getPositionDimensionIndex()
function to get Position Dimension Index
void setMotorParameters(long type, long current_c_mA, long current_out_mA, char pole_pairs, long time_ds)
function to SET motor parameters
long getPositionNotationIndex()
function to get Position Notation Index
void shutdown()
function to reach ready_to_switch_on state
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
int16_t computeChecksum(int16_t *pDataArray, int16_t numberOfWords)
function to compute EPOS2 checksum
static Ftdi::Context ftdi
a reference to the FTDI USB device
int32_t readObject(int16_t index, int8_t subindex)
function to read an object from the EPOS2
long getMinPositionLimit()
function to GET the Min Position Limit
long readEncoderCounterAtIndexPulse()
function to read the Encoder Counter at index pulse
long getEncoderPulseNumber()
function to GET the Encoder Pulses
int getDigInPolarity()
Gives Digital Inputs Polarity Mask.
long getVelocityPGain()
function to get P Velocity Gain
void setPositionNotationIndex(long notation)
function to set Position Notation Index
void readErrorHistory(long *error[5])
function to read last 5 errors
void setAnalogOutput1(long voltage_mV)
function to set analog output 1
void setMotorType(long type)
function to SET Motor type
void setMaxPositionLimit(long limit)
function to SET the Max Position Limit
long getMotorType()
function to GET Motor type
void startCurrent()
[OPMODE=current] function to move the motor in current mode
long getPositionIGain()
function to get I Position Gain
void setPositionDGain(long gain)
function to set D Position Gain
long getTargetProfileVelocity()
[OPMODE=profile_velocity] function to get the velocity
EPOS2IOException(const std::string &error_description)
void switchOn()
function to reach switch_on state
void setAccelerationDimensionIndex(long Dimension)
function to set Acceleration Dimension Index
long getProfileQuickStopDecel(void)
function to GET the Quick Stop Deceleration in profile
static const std::string error_names[]
Strings of generic error descriptions.
void setVerbose(bool verbose)
void setOperationMode(long opmode)
function to set the operation mode
void setVelocityNotationIndex(long notation)
function to set Velocity Notation Index
void enableOperation()
function to reach operation_enable state and enables power on motor
long getProfileMaxVelocity(void)
function to GET the Max Velocity allowed in Profile
void setMaxAcceleration(long max_acceleration)
function to SET Max Acceleration
long readCurrent()
function to read motor current
long getNegativeLong(long number)
function to make a unsigned long signed
void setProfileType(long type)
function to SET the type in profile
void setVelocityWindow(long window_rm)
function to set Velocity Window
long readVersionSoftware()
function to read the software version
int getDigInStateMask()
Gives Digital Inputs State Mask.
void setThermalTimeCtWinding(long time_ds)
function to SET Motor Thermal Time Constant Winding
long getAccelerationDimensionIndex()
function to get Acceleration Dimension Index
void setPositionAFFGain(long gain)
function to set Acceleration Feed Forward Position Gain
void setVelocityWindowTime(long time_ms)
function to set Velocity Window Time
long getAnalogOutput1()
function to get the value in the Analog Output1
long readVelocityDemand()
function to read velocity demand
long getProfileAcceleration(void)
function to GET the Acceleration in profile
void setRS232FrameTimeout(long timeout)
function to SET the RS232 Frame Timeout
int writeObject(int16_t index, int8_t subindex, int32_t data)
function to write an object to the EPOS2
static void * threadTargetReached(void *param)
Thread listens to target reached.
long getRS232Baudrate()
function to GET the RS232 Baudrate
void faultReset()
function to reach switch_on_disabled state after a FAULT
void setTargetProfileVelocity(long velocity)
[OPMODE=profile_velocity] function to set the velocity
void disablePositionLimits(void)
function to DISABLE Position Limits
void setAccelerationNotationIndex(long notation)
function to set Acceleration Notation Index
long readHallsensorPattern()
function to read the Hall Sensor Pattern
long getPositionPGain()
function to get P Position Gain
void setPositionPGain(long gain)
function to set P Position Gain
void setCurrentIGain(long gain)
function to set I Current Gain
void setProfileDeceleration(long deceleration)
function to SET the Deceleration in profile
long getProfileType(void)
function to GET the type in profile
std::string getOpModeDescription(long opmode)
function to show the name of the operation mode
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
long getVelocitySetPointFactorPGain()
function to GET Speed Regulator Set Point Factor P Velocity Gain
static const std::string error_descriptions[]
error descriptions
void setMotorContinuousCurrentLimit(long current_mA)
function to SET Motor Continous Current Limit
long getOperationMode()
function to know which operation mode is set
void setUSBFrameTimeout(long timeout)
function to SET the USB Frame Timeout
long readCurrentAveraged()
function to read motor averaged current
void startVelocity()
function to move the motor in Velocity mode
void stopProfileVelocity()
[OPMODE=profile_velocity] function to stop the motor
static bool ftdi_initialized
long getVelocityWindowTime()
function to get Velocity Window Time
void restoreDefaultParameters()
function to restore default parameters of EPOS2.
long getCurrentPGain()
function to get P Current Gain
std::string searchErrorDescription(long error_code)
given an error code it returns its description
void setProfileMaxVelocity(long velocity)
function to SET the Max Velocity allowed in Profile
void enableController()
function to facititate transitions from the start of the controller to switch it on ...
long getVelocityNotationIndex()
function to get Velocity Notation Index
void saveParameters()
function to save all parameters in EEPROM
void stopCurrent()
[OPMODE=current] function to stop the motor in current mode
EPOS2UnknownStateException(const std::string &error_description)
long getHomePosition()
function to get the Home position
void close()
Disconnects hardware.
void quickStop()
function to reach switch_on state
void disableVoltage()
function to reach switch_on_disabled state
void sendFrame(int16_t *frame)
function send a frame to EPOS2
void setTargetCurrent(long current)
[OPMODE=current] function to SET the target current
void setPositionVFFGain(long gain)
function to set Velocity Feed Forward Position Gain
Implementation of a driver for EPOS2 Motor Controller.
void init()
Connects hardware.
void p(const char *text)
function to make a unsigned long signed
long getProfileDeceleration(void)
function to GET the Deceleration in profile
void setHome()
function to set a Home position with user interaction
long getProfileVelocity(void)
function to GET the velocity of the Velocity Profile
void setProfileVelocity(long velocity)
function to SET the velocity of the Velocity Profile
long getTargetProfilePosition()
function to GET the target position
long readVersionHardware()
function to read the hardware version
long readEncoderCounter()
function to read the Encoder Counter
void receiveFrame(uint16_t *ans_frame)
function receive a frame from EPOS2
long getVelocityDimensionIndex()
function to get Velocity Dimension Index
long getMotorContinuousCurrentLimit()
function to GET Motor Continous Current Limit
long readFollowingError()
function to read the Following Error
long getAccelerationNotationIndex()
function to get Acceleration Notation Index
void setVelocityPGain(long gain)
function to set P Velocity Gain
long getMaxPositionLimit()
function to GET the Max Position Limit
CEpos2(int8_t nodeId=0x00)
Constructor.
void setMotorOutputCurrentLimit(long current_mA)
function to SET Motor Output Current Limit
long getCurrentIGain()
function to get I Current Gain
int32_t readPosition()
function to read motor position
void setProfileAcceleration(long acceleration)
function to SET the Acceleration in profile
void setPositionIGain(long gain)
function to set I Position Gain
long getPositionDGain()
function to get D Position Gain
void setProfileQuickStopDecel(long deceleration)
function to SET the Quick Stop Deceleration in profile
EPOS2OpenException(const std::string &error_description)
long getPositionVFFGain()
function to get Velocity Feed Forward Position Gain
void setEncoderPulseNumber(long pulses)
function to SET the Encoder Pulses
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
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.
long getMotorPolePairNumber()
function to GET Motor Pole Pair Number
void setPositionDimensionIndex(long Dimension)
function to set Position Dimension Index
void stopVelocity()
function to stop the motor in velocity mode
void stopHoming()
stops a homing operation
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
void setTargetVelocity(long velocity)
function to SET the target velocity
long readVelocity()
function to read motor average velocity
void startProfileVelocity()
[OPMODE=profile_velocity] function to move the motor in a velocity
void openDevice()
open EPOS2 device using CFTDI
void setMotorPolePairNumber(char pole_pairs)
function to SET Motor Pole Pair Number
long getTargetVelocity()
function to GET the target velocity This function gets the target velocity of velocity operation mode...
void setEncoderType(long type)
function to SET the Encoder type
void setEncoderPolarity(long polarity)
function to SET the Encoder polarity
void setMaxFollowingError(long follerror)
function to SET the Max Following Error
void doHoming(bool blocking=false)
starts a homing operation
int getDigInFuncMask()
Gives Digital Inputs Functionalities Mask.
void getMotorParameters(long &type, long ¤t_c_mA, long ¤t_out_mA, char &pole_pairs, long &time_ds)
function to GET encoder parameters
bool isTargetReached()
function to know if the motor has reached the target position or velocity
void setVelocityDimensionIndex(long Dimension)
function to set Velocity Dimension Index
void setEncoderParameters(long pulses, long type, long polarity)
function to SET encoder parameters
long getPositionWindow()
function to get Position Window
long readVelocityActual()
function to read velocity sensor actual
long getTargetCurrent()
[OPMODE=current] function to GET the target current
long getMotorOutputCurrentLimit()
function to GET Motor Output Current Limit
long getVelocityWindow()
function to get Velocity Window
long getEncoderPolarity()
function to GET the Encoder Pulses
void getMovementInfo()
prints information about movement
int getDigInState(int digitalIN=2)
Gives the state of a certain digital Input.
long getVelocityIGain()
function to get I Velocity Gain
long getEncoderType()
function to GET the Encoder Pulses
void setTargetProfilePosition(long position)
function to SET the target position
long getRS232FrameTimeout()
function to GET the RS232 Frame Timeout
long getPositionMarker(int buffer=0)
gets the position marked by the sensor
static const int error_codes[]
error integer codes