#include <CanDriveHarmonica.h>
Classes | |
struct | ParamCanOpenType |
struct | ParamType |
Public Types | |
enum | StateHarmonica { ST_PRE_INITIALIZED, ST_OPERATION_ENABLED, ST_OPERATION_DISABLED, ST_MOTOR_FAILURE } |
Public Member Functions | |
CanDriveHarmonica () | |
bool | disableBrake (bool bDisabled) |
bool | endHoming () |
bool | evalReceivedMsg (CanMsg &msg) |
bool | evalReceivedMsg () |
void | evalSDO (CanMsg &CMsg, int *pIndex, int *pSubindex) |
bool | execHoming () |
void | getData (double *pdPosGearRad, double *pdVelGearRadS, int *piTorqueCtrl, int *piStatusCtrl) |
unsigned int | getError () |
void | getGearDeltaPosVelRadS (double *pdDeltaAngleGearRad, double *pdVelGearRadS) |
void | getGearPosRad (double *pdPosGearRad) |
void | getGearPosVelRadS (double *pdAngleGearRad, double *pdVelGearRadS) |
void | getMotorTorque (double *dTorqueNm) |
int | getSDODataInt32 (CanMsg &CMsg) |
void | getStatus (int *piStatus, int *piTempCel) |
bool | getStatusLimitSwitch () |
double | getTimeToLastMsg () |
bool | init () |
bool | initHoming () |
void | IntprtSetFloat (int iDataLen, char cCmdChar1, char cCmdChar2, int iIndex, float fData) |
void | IntprtSetInt (int iDataLen, char cCmdChar1, char cCmdChar2, int iIndex, int iData) |
bool | isError () |
bool | isInitialized () |
void | requestMotorTorque () |
void | requestPosVel () |
void | requestStatus () |
bool | reset () |
bool | resetEMStop () |
void | sendHeartbeat () |
void | sendSDOAbort (int iObjIndex, int iObjSubIndex, unsigned int iErrorCode) |
void | sendSDODownload (int iObjIndex, int iObjSub, int iData) |
void | sendSDOUpload (int iObjIndex, int iObjSub) |
void | setCanItf (CanItf *pCanItf) |
void | setCanOpenParam (int iTxPDO1, int iTxPDO2, int iRxPDO2, int iTxSDO, int iRxSDO) |
void | setDriveParam (DriveParam driveParam) |
bool | setEMStop () |
void | setGearPosVelRadS (double dPosRad, double dVelRadS) |
void | setGearVelRadS (double dVelEncRadS) |
void | setMotorTorque (double dTorqueNm) |
int | setRecorder (int iFlag, int iParam=0, std::string sParam="/home/MyLog_") |
bool | setTypeMotion (int iType) |
bool | shutdown () |
bool | start () |
bool | startWatchdog (bool bStarted) |
bool | stop () |
Protected Member Functions | |
double | estimVel (double dPos) |
void | evalMotorFailure (int iFailure) |
bool | evalStatusRegister (int iStatus) |
void | finishedSDOSegmentedTransfer () |
bool | isBitSet (int iVal, int iNrBit) |
int | receivedSDODataSegment (CanMsg &msg) |
int | receivedSDOSegmentedInitiation (CanMsg &msg) |
void | receivedSDOTransferAbort (unsigned int iErrorCode) |
void | sendSDOUploadSegmentConfirmation (bool toggleBit) |
Protected Attributes | |
ElmoRecorder * | ElmoRec |
bool | m_bCurrentLimitOn |
bool | m_bIsInitialized |
bool | m_bLimitSwitchEnabled |
bool | m_bLimSwLeft |
bool | m_bLimSwRight |
bool | m_bOutputOfFailure |
bool | m_bWatchdogActive |
CanMsg | m_CanMsgLast |
TimeStamp | m_CurrentTime |
double | m_dAngleGearRadMem |
double | m_dMotorCurr |
double | m_dOldPos |
double | m_dPosGearMeasRad |
DriveParam | m_DriveParam |
double | m_dVelGearMeasRadS |
TimeStamp | m_FailureStartTime |
int | m_iCountRequestDiv |
int | m_iDistSteerAxisToDriveWheelMM |
int | m_iMotorState |
int | m_iNewMotorState |
int | m_iNumAttempsRecFail |
int | m_iPartnerDriveRatio |
int | m_iStatusCtrl |
int | m_iTorqueCtrl |
int | m_iTypeMotion |
ParamType | m_Param |
ParamCanOpenType | m_ParamCanOpen |
CanItf * | m_pCanCtrl |
TimeStamp | m_SendTime |
std::string | m_sErrorMessage |
TimeStamp | m_StartTime |
TimeStamp | m_VelCalcTime |
TimeStamp | m_WatchdogTime |
segData | seg_Data |
Driver class for the motor drive of type Harmonica.
Definition at line 72 of file CanDriveHarmonica.h.
States of the drive.
Definition at line 89 of file CanDriveHarmonica.h.
Default constructor.
Definition at line 62 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::disableBrake | ( | bool | bDisabled | ) | [virtual] |
Disables the brake. This function is not implemented for Harmonica, because brakes are released upon power on and shut only at emergency stop.
Implements CanDriveItf.
Definition at line 513 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::endHoming | ( | ) |
Performs homing procedure Drives wheel in neutral Position for Startup.
double CanDriveHarmonica::estimVel | ( | double | dPos | ) | [protected] |
Definition at line 1171 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::evalMotorFailure | ( | int | iFailure | ) | [protected] |
Definition at line 1290 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::evalReceivedMsg | ( | CanMsg & | msg | ) | [virtual] |
Evals a received message. Only messages with fitting identifiers are evaluated.
msg | message to be evaluated. |
Implements CanDriveItf.
Definition at line 114 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::evalReceivedMsg | ( | ) | [inline, virtual] |
Evals received messages in OBJECT mode.
Implements CanDriveItf.
Definition at line 205 of file CanDriveHarmonica.h.
void CanDriveHarmonica::evalSDO | ( | CanMsg & | CMsg, |
int * | pIndex, | ||
int * | pSubindex | ||
) |
CANopen: Evaluates a service data object and gives back object and sub-object ID
Definition at line 1054 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::evalStatusRegister | ( | int | iStatus | ) | [protected] |
Definition at line 1188 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::execHoming | ( | ) | [virtual] |
Performs homing procedure.
Implements CanDriveItf.
Definition at line 583 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::finishedSDOSegmentedTransfer | ( | ) | [protected] |
CANopen: Give the collected data of a finished segmented SDO transfer to an appropriate (depending on the current object ID) processing function. Function is called by receivedSDODataSegment, when the transfer is finished. Currently, only Elmo Recorder data is uploaded segmented and is processed here.
Definition at line 1156 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::getData | ( | double * | pdPosGearRad, |
double * | pdVelGearRadS, | ||
int * | piTorqueCtrl, | ||
int * | piStatusCtrl | ||
) |
Returns some received values from the drive.
pdPosGearRad | position of the drive |
pdVelGearRadS | velocity of the drive |
piTorqueCtrl | torque |
piStatusCtrl |
Definition at line 784 of file CanDriveHarmonica.cpp.
unsigned int CanDriveHarmonica::getError | ( | ) | [inline, virtual] |
Return a bitfield containing information about the pending errors.
Implements CanDriveItf.
Definition at line 254 of file CanDriveHarmonica.h.
void CanDriveHarmonica::getGearDeltaPosVelRadS | ( | double * | pdDeltaAngleGearRad, |
double * | pdVelGearRadS | ||
) | [virtual] |
Returns the change of the position and the velocity. The given delta position is given since the last call of this function.
Implements CanDriveItf.
Definition at line 776 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::getGearPosRad | ( | double * | pdPosGearRad | ) | [virtual] |
Returns the current position.
Implements CanDriveItf.
Definition at line 763 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::getGearPosVelRadS | ( | double * | pdAngleGearRad, |
double * | pdVelGearRadS | ||
) | [virtual] |
Returns the position and the velocity of the drive.
Implements CanDriveItf.
Definition at line 769 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::getMotorTorque | ( | double * | dTorqueNm | ) | [virtual] |
Return member variable m_MotorCurrent To update this value call requestMotorCurrent at first
Implements CanDriveItf.
Definition at line 1378 of file CanDriveHarmonica.cpp.
int CanDriveHarmonica::getSDODataInt32 | ( | CanMsg & | CMsg | ) |
Internal use.
Definition at line 1061 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::getStatus | ( | int * | piStatus, |
int * | piTempCel | ||
) | [inline, virtual] |
Dummy implementation for completing CanDriveItf.
Implements CanDriveItf.
Definition at line 272 of file CanDriveHarmonica.h.
bool CanDriveHarmonica::getStatusLimitSwitch | ( | ) | [virtual] |
Returns the status of the limit switch needed for homing. true = limit switch is reached; false = not reached
Implements CanDriveItf.
Definition at line 526 of file CanDriveHarmonica.cpp.
double CanDriveHarmonica::getTimeToLastMsg | ( | ) | [virtual] |
Returns the elapsed time since the last received message.
Implements CanDriveItf.
Definition at line 519 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::init | ( | ) | [virtual] |
Initializes the driver. Call this function once after construction.
Implements CanDriveItf.
Definition at line 290 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::initHoming | ( | ) | [virtual] |
Inits homing procedure.
Implements CanDriveItf.
Definition at line 531 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::IntprtSetFloat | ( | int | iDataLen, |
char | cCmdChar1, | ||
char | cCmdChar2, | ||
int | iIndex, | ||
float | fData | ||
) |
Sends a float value to the Harmonica using the built in interpreter.
Definition at line 944 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::IntprtSetInt | ( | int | iDataLen, |
char | cCmdChar1, | ||
char | cCmdChar2, | ||
int | iIndex, | ||
int | iData | ||
) | [virtual] |
Sends an integer value to the Harmonica using the built in interpreter.
Implements CanDriveItf.
Definition at line 922 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::isBitSet | ( | int | iVal, |
int | iNrBit | ||
) | [inline, protected] |
Definition at line 456 of file CanDriveHarmonica.h.
bool CanDriveHarmonica::isError | ( | ) | [virtual] |
Returns true if an error has been detected.
Implements CanDriveItf.
Definition at line 830 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::isInitialized | ( | ) | [inline, virtual] |
Check if the driver is already initialized. This is necessary if a drive gets switched off during runtime.
Implements CanDriveItf.
Definition at line 126 of file CanDriveHarmonica.h.
int CanDriveHarmonica::receivedSDODataSegment | ( | CanMsg & | msg | ) | [protected] |
CANopen: Segment data is stored to the SDOSegmented container. Function is called, when a segment during a segmented SDO transfer is received (by evalReceivedMsg). It analyzes the SDO transfer header to see, if the transfer is finished. If it's not finished, sendSDOUploadSegmentConfirmation is called to confirm the receive of the current segment and request the next one. -Currently only used for Elmo Recorder read-out
Definition at line 1092 of file CanDriveHarmonica.cpp.
int CanDriveHarmonica::receivedSDOSegmentedInitiation | ( | CanMsg & | msg | ) | [protected] |
CANopen: Evaluates a service data object and gives back object and sub-object ID. Function is called, when a SDO initialize transfer segment is received (by evalReceivedMsg)
Definition at line 1070 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::receivedSDOTransferAbort | ( | unsigned int | iErrorCode | ) | [protected] |
CANopen: Function is called by evalReceivedMsg when the current segmented SDO transfer is cancelled with an error code.
Definition at line 996 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::requestMotorTorque | ( | ) | [virtual] |
Sends Requests for "active current" to motor via CAN To read Motor current perform the following: 1.) request motor current m_pW1DriveMotor->requestMotorTorque(); 2.) evaluate Can buffer to read motor current and decode it evalCanBuffer();
Implements CanDriveItf.
Definition at line 822 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::requestPosVel | ( | ) | [virtual] |
Dummy implementation for completing CanDriveItf.
Implements CanDriveItf.
Definition at line 794 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::requestStatus | ( | ) | [virtual] |
Requests status :) checks whether motor is operational, switched off or in error state. If motor is in which error state it checks which error occured
Implements CanDriveItf.
Definition at line 816 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::reset | ( | ) | [virtual] |
Resets the drive. The drive changes into the state after initializaton.
Implements CanDriveItf.
Definition at line 432 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::resetEMStop | ( | ) | [inline, virtual] |
Disable the emergency stop.
Implements CanDriveItf.
Definition at line 318 of file CanDriveHarmonica.h.
void CanDriveHarmonica::sendHeartbeat | ( | ) |
Sends a heartbeat to the CAN-network to keep all listening watchdogs sleeping
Definition at line 806 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::sendSDOAbort | ( | int | iObjIndex, |
int | iObjSubIndex, | ||
unsigned int | iErrorCode | ||
) |
CANopen: This protocol cancels an active segmented transmission due to the given Error Code
Definition at line 972 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::sendSDODownload | ( | int | iObjIndex, |
int | iObjSub, | ||
int | iData | ||
) |
CANopen: Downloads a service data object (master to device). (in expedited transfer mode, means in only one message)
Definition at line 1026 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::sendSDOUpload | ( | int | iObjIndex, |
int | iObjSub | ||
) |
CANopen: Uploads a service data object (device to master). (in expedited transfer mode, means in only one message)
Definition at line 1002 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::sendSDOUploadSegmentConfirmation | ( | bool | toggleBit | ) | [protected] |
CANopen: Answer a data mesage during a segmented SDO transfer including a toggling bit. Current toggle bit is stored in the SDOSegmented container. Function is called, when any SDO transfer segment is received (by receivedSDODataSegment)
Definition at line 1131 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::setCanItf | ( | CanItf * | pCanItf | ) | [inline, virtual] |
void CanDriveHarmonica::setCanOpenParam | ( | int | iTxPDO1, |
int | iTxPDO2, | ||
int | iRxPDO2, | ||
int | iTxSDO, | ||
int | iRxSDO | ||
) |
Sets the CAN identifiers of the drive node.
iTxPDO1 | first transmit process data object |
iTxPDO2 | second transmit process data object |
iRxPDO2 | second receive process data object |
iTxSDO | transmit service data object |
iRxSDO | receive service data object |
Definition at line 103 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::setDriveParam | ( | DriveParam | driveParam | ) | [inline, virtual] |
Sets the drive parameter.
Implements CanDriveItf.
Definition at line 244 of file CanDriveHarmonica.h.
bool CanDriveHarmonica::setEMStop | ( | ) | [inline, virtual] |
Enable the emergency stop.
Implements CanDriveItf.
Definition at line 313 of file CanDriveHarmonica.h.
void CanDriveHarmonica::setGearPosVelRadS | ( | double | dPosRad, |
double | dVelRadS | ||
) | [virtual] |
Sets required position and veolocity. Use this function only in position mode.
Implements CanDriveItf.
Definition at line 655 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::setGearVelRadS | ( | double | dVelEncRadS | ) | [virtual] |
Sets the velocity. By calling the function the status is requested, too.
Implements CanDriveItf.
Definition at line 706 of file CanDriveHarmonica.cpp.
void CanDriveHarmonica::setMotorTorque | ( | double | dTorqueNm | ) | [virtual] |
Sets MotorTorque in Nm By sending this command the status is requested, too
Implements CanDriveItf.
Definition at line 1327 of file CanDriveHarmonica.cpp.
int CanDriveHarmonica::setRecorder | ( | int | iFlag, |
int | iParam = 0 , |
||
std::string | sParam = "/home/MyLog_" |
||
) | [virtual] |
Provides several functions for drive information recording purposes using the built in ElmoRecorder, which allows to record drive information at a high frequency.
iFlag | To keep the interface slight, use iParam to command the recorder: 0: Configure the Recorder to record the sources Main Speed(1), Main position(2), Active current(10), Speed command(16). With iParam = iRecordingGap you specify every which time quantum (4*90usec) a new data point (of 1024 points in total) is recorded; 1: Query Upload of recorded source (1=Main Speed, 2=Main position, 10=Active Current, 16=Speed command) with iParam and log data to file sParam = file prefix. Filename is extended with _MotorNumber_RecordedSource.log 2: Request status of ongoing readout process 99: Abort and clear current SDO readout process |
overwrites previous collected data (even from other processes)
Implements CanDriveItf.
Definition at line 1392 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::setTypeMotion | ( | int | iType | ) | [virtual] |
Sets the motion type drive.
Implements CanDriveItf.
Definition at line 854 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::shutdown | ( | ) | [virtual] |
bool CanDriveHarmonica::start | ( | ) | [virtual] |
Enables the motor. After calling the drive accepts velocity and position commands.
Implements CanDriveItf.
Definition at line 377 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::startWatchdog | ( | bool | bStarted | ) | [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 done in function setGearVelRadS().
Implements CanDriveItf.
Definition at line 460 of file CanDriveHarmonica.cpp.
bool CanDriveHarmonica::stop | ( | ) | [virtual] |
Disables the motor. After calling the drive won't accepts velocity and position commands.
Implements CanDriveItf.
Definition at line 368 of file CanDriveHarmonica.cpp.
ElmoRecorder* CanDriveHarmonica::ElmoRec [protected] |
Definition at line 403 of file CanDriveHarmonica.h.
bool CanDriveHarmonica::m_bCurrentLimitOn [protected] |
Definition at line 432 of file CanDriveHarmonica.h.
bool CanDriveHarmonica::m_bIsInitialized [protected] |
Definition at line 438 of file CanDriveHarmonica.h.
bool CanDriveHarmonica::m_bLimitSwitchEnabled [protected] |
Definition at line 396 of file CanDriveHarmonica.h.
bool CanDriveHarmonica::m_bLimSwLeft [protected] |
Definition at line 420 of file CanDriveHarmonica.h.
bool CanDriveHarmonica::m_bLimSwRight [protected] |
Definition at line 421 of file CanDriveHarmonica.h.
bool CanDriveHarmonica::m_bOutputOfFailure [protected] |
Definition at line 436 of file CanDriveHarmonica.h.
bool CanDriveHarmonica::m_bWatchdogActive [protected] |
Definition at line 442 of file CanDriveHarmonica.h.
CanMsg CanDriveHarmonica::m_CanMsgLast [protected] |
Definition at line 401 of file CanDriveHarmonica.h.
TimeStamp CanDriveHarmonica::m_CurrentTime [protected] |
Definition at line 409 of file CanDriveHarmonica.h.
double CanDriveHarmonica::m_dAngleGearRadMem [protected] |
Definition at line 416 of file CanDriveHarmonica.h.
double CanDriveHarmonica::m_dMotorCurr [protected] |
Definition at line 440 of file CanDriveHarmonica.h.
double CanDriveHarmonica::m_dOldPos [protected] |
Definition at line 423 of file CanDriveHarmonica.h.
double CanDriveHarmonica::m_dPosGearMeasRad [protected] |
Definition at line 418 of file CanDriveHarmonica.h.
DriveParam CanDriveHarmonica::m_DriveParam [protected] |
Definition at line 395 of file CanDriveHarmonica.h.
double CanDriveHarmonica::m_dVelGearMeasRadS [protected] |
Definition at line 417 of file CanDriveHarmonica.h.
TimeStamp CanDriveHarmonica::m_FailureStartTime [protected] |
Definition at line 412 of file CanDriveHarmonica.h.
int CanDriveHarmonica::m_iCountRequestDiv [protected] |
Definition at line 430 of file CanDriveHarmonica.h.
int CanDriveHarmonica::m_iDistSteerAxisToDriveWheelMM [protected] |
Definition at line 454 of file CanDriveHarmonica.h.
int CanDriveHarmonica::m_iMotorState [protected] |
Definition at line 427 of file CanDriveHarmonica.h.
int CanDriveHarmonica::m_iNewMotorState [protected] |
Definition at line 428 of file CanDriveHarmonica.h.
int CanDriveHarmonica::m_iNumAttempsRecFail [protected] |
Definition at line 434 of file CanDriveHarmonica.h.
int CanDriveHarmonica::m_iPartnerDriveRatio [protected] |
Definition at line 453 of file CanDriveHarmonica.h.
int CanDriveHarmonica::m_iStatusCtrl [protected] |
Definition at line 406 of file CanDriveHarmonica.h.
int CanDriveHarmonica::m_iTorqueCtrl [protected] |
Definition at line 407 of file CanDriveHarmonica.h.
int CanDriveHarmonica::m_iTypeMotion [protected] |
Definition at line 405 of file CanDriveHarmonica.h.
ParamType CanDriveHarmonica::m_Param [protected] |
Definition at line 397 of file CanDriveHarmonica.h.
ParamCanOpenType CanDriveHarmonica::m_ParamCanOpen [protected] |
Definition at line 394 of file CanDriveHarmonica.h.
CanItf* CanDriveHarmonica::m_pCanCtrl [protected] |
Definition at line 400 of file CanDriveHarmonica.h.
TimeStamp CanDriveHarmonica::m_SendTime [protected] |
Definition at line 413 of file CanDriveHarmonica.h.
std::string CanDriveHarmonica::m_sErrorMessage [protected] |
Definition at line 425 of file CanDriveHarmonica.h.
TimeStamp CanDriveHarmonica::m_StartTime [protected] |
Definition at line 414 of file CanDriveHarmonica.h.
TimeStamp CanDriveHarmonica::m_VelCalcTime [protected] |
Definition at line 411 of file CanDriveHarmonica.h.
TimeStamp CanDriveHarmonica::m_WatchdogTime [protected] |
Definition at line 410 of file CanDriveHarmonica.h.
segData CanDriveHarmonica::seg_Data [protected] |
Definition at line 444 of file CanDriveHarmonica.h.