Public Types | Public Member Functions
CanDriveItf Class Reference

#include <CanDriveItf.h>

Inheritance diagram for CanDriveItf:
Inheritance graph
[legend]

List of all members.

Public Types

enum  MotionType { MOTIONTYPE_VELCTRL, MOTIONTYPE_TORQUECTRL, MOTIONTYPE_POSCTRL }

Public Member Functions

virtual bool disableBrake (bool bDisabled)=0
virtual bool evalReceivedMsg (CanMsg &msg)=0
virtual bool evalReceivedMsg ()=0
virtual bool execHoming ()=0
virtual unsigned int getError ()=0
virtual void getGearDeltaPosVelRadS (double *pdDeltaAngleGearRad, double *pdVelGearRadS)=0
virtual void getGearPosRad (double *pdPosGearRad)=0
virtual void getGearPosVelRadS (double *pdAngleGearRad, double *pdVelGearRadS)=0
virtual void getMotorTorque (double *dTorqueNm)=0
virtual void getStatus (int *piStatus, int *piTempCel)=0
virtual bool getStatusLimitSwitch ()=0
virtual double getTimeToLastMsg ()=0
virtual bool init ()=0
virtual bool initHoming ()=0
virtual void IntprtSetInt (int iDataLen, char cCmdChar1, char cCmdChar2, int iIndex, int iData)=0
virtual bool isError ()=0
virtual bool isInitialized ()=0
virtual void requestMotorTorque ()=0
virtual void requestPosVel ()=0
virtual void requestStatus ()=0
virtual bool reset ()=0
virtual bool resetEMStop ()=0
virtual void setCanItf (CanItf *pCanItf)=0
virtual void setDriveParam (DriveParam driveParam)=0
virtual bool setEMStop ()=0
virtual void setGearPosVelRadS (double dPosRad, double dVelRadS)=0
virtual void setGearVelRadS (double dVelRadS)=0
virtual void setMotorTorque (double dTorqueNm)=0
virtual int setRecorder (int iFlag, int iParam=0, std::string sParam="/home/MyLog")=0
virtual bool setTypeMotion (int iType)=0
virtual bool shutdown ()=0
virtual bool start ()=0
virtual bool startWatchdog (bool bStarted)=0
virtual bool stop ()=0

Detailed Description

Interface for a drive.

Definition at line 68 of file CanDriveItf.h.


Member Enumeration Documentation

Motion type of the controller.

Enumerator:
MOTIONTYPE_VELCTRL 
MOTIONTYPE_TORQUECTRL 
MOTIONTYPE_POSCTRL 

Definition at line 74 of file CanDriveItf.h.


Member Function Documentation

virtual bool CanDriveItf::disableBrake ( bool  bDisabled) [pure virtual]

Disables the brake. This function is not implemented for Harmonica, because brakes are released upon power on and shut only at emergency stop.

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::evalReceivedMsg ( CanMsg msg) [pure virtual]

Evals a received message. Only messages with fitting identifiers are evaluated.

Parameters:
msgmessage to be evaluated.

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::evalReceivedMsg ( ) [pure virtual]

Evals received messages in OBJECT mode. The CAN drives have to implement which identifiers they are interested in.

Returns:
true on success, false on failure.

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::execHoming ( ) [pure virtual]

Performs homing procedure. Used only in position mode.

Implemented in CanDriveHarmonica.

virtual unsigned int CanDriveItf::getError ( ) [pure virtual]

Return a bitfield containing information about the pending errors.

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::getGearDeltaPosVelRadS ( double *  pdDeltaAngleGearRad,
double *  pdVelGearRadS 
) [pure virtual]

Returns the change of the position and the velocity. The given delta position is given since the last call of this function.

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::getGearPosRad ( double *  pdPosGearRad) [pure virtual]

Returns the current position.

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::getGearPosVelRadS ( double *  pdAngleGearRad,
double *  pdVelGearRadS 
) [pure virtual]

Returns the position and the velocity of the drive.

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::getMotorTorque ( double *  dTorqueNm) [pure virtual]

Returns member variable m_MotorCurrent To update this value call requestMotorCurrent before and evaluate CAN buffer, or wait one cycle

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::getStatus ( int *  piStatus,
int *  piTempCel 
) [pure virtual]

Returns the measured temperature.

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::getStatusLimitSwitch ( ) [pure virtual]

Returns the status of the limit switch needed for homing. true = limit switch is reached; false = not reached

Implemented in CanDriveHarmonica.

virtual double CanDriveItf::getTimeToLastMsg ( ) [pure virtual]

Returns the elapsed time since the last received message.

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::init ( ) [pure virtual]

Initializes the driver. Call this function once after construction.

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::initHoming ( ) [pure virtual]

Inits homing procedure. Used only in position mode.

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::IntprtSetInt ( int  iDataLen,
char  cCmdChar1,
char  cCmdChar2,
int  iIndex,
int  iData 
) [pure virtual]

Sends an integer value to the Harmonica using the built in interpreter. cpc-kischa

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::isError ( ) [pure virtual]

Returns true if an error has been detected.

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::isInitialized ( ) [pure virtual]

Check if the driver is already initialized. This is necessary if a drive gets switched off during runtime.

Returns:
true if initialization occured already, false if not.

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::requestMotorTorque ( ) [pure virtual]

Sends Requests for "active current" to motor via CAN

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::requestPosVel ( ) [pure virtual]

Requests position and velocity.

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::requestStatus ( ) [pure virtual]

Requests status.

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::reset ( ) [pure virtual]

Resets the drive. The drive changes into the state after initializaton.

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::resetEMStop ( ) [pure virtual]

Disable the emergency stop.

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::setCanItf ( CanItf pCanItf) [pure virtual]

Sets the CAN interface.

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::setDriveParam ( DriveParam  driveParam) [pure virtual]

Sets the drive parameter.

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::setEMStop ( ) [pure virtual]

Enable the emergency stop.

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::setGearPosVelRadS ( double  dPosRad,
double  dVelRadS 
) [pure virtual]

Sets required position and veolocity. Use this function only in position mode. By calling the function the status is requested, too.

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::setGearVelRadS ( double  dVelRadS) [pure virtual]

Sets the velocity. By calling the function the status is requested, too.

Implemented in CanDriveHarmonica.

virtual void CanDriveItf::setMotorTorque ( double  dTorqueNm) [pure virtual]

Sends command for motor Torque (in Nm)

Implemented in CanDriveHarmonica.

virtual int CanDriveItf::setRecorder ( int  iFlag,
int  iParam = 0,
std::string  sParam = "/home/MyLog" 
) [pure virtual]

Provides several functions for drive information recording purposes. By now, only implemented for the Elmo-recorder. cpc-pk

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::setTypeMotion ( int  iType) [pure virtual]

Sets the motion type drive. The function is not implemented for Harmonica. The harmonica drive is configured just for velocity mode.

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::shutdown ( ) [pure virtual]

Shutdowns the motor.

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::start ( ) [pure virtual]

Enables the motor. After calling the drive accepts velocity and position commands.

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::startWatchdog ( bool  bStarted) [pure virtual]

Starts the watchdog. The Harmonica provides watchdog functionality which means the drive stops if the watchdog becomes active. To keep the watchdog inactive a heartbeat message has to be sent periodically. The update rate is set to 1s. The update is is done in function setGearVelRadS().

Implemented in CanDriveHarmonica.

virtual bool CanDriveItf::stop ( ) [pure virtual]

Disables the motor. After calling the drive won't accepts velocity and position commands.

Implemented in CanDriveHarmonica.


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


cob_canopen_motor
Author(s): Christian Connette
autogenerated on Sun Oct 5 2014 23:02:12