#include <CanCtrlPltfCOb3.h>
|
| | CanCtrlPltfCOb3 (std::string iniDirectory) |
| |
| int | ElmoRecordings (int iFlag, int iParam, std::string sString) |
| |
| int | evalCanBuffer () |
| |
| int | getGearDeltaPosVelRadS (int iCanIdent, double *pdDeltaAngleGearRad, double *pdVelGearRadS) |
| |
| int | getGearPosVelRadS (int iCanIdent, double *pdAngleGearRad, double *pdVelGearRadS) |
| |
| void | getMotorTorque (int iCanIdent, double *pdTorqueNm) |
| |
| void | getStatus (int iCanIdent, int *piStatus, int *piTempCel) |
| |
| bool | initPltf () |
| |
| bool | isPltfError () |
| |
| void | requestDriveStatus () |
| |
| void | requestMotorTorque () |
| |
| int | requestMotPosVel (int iCanIdent) |
| |
| bool | resetPltf () |
| |
| void | setMotorTorque (int iCanIdent, double dTorqueNm) |
| |
| int | setVelGearRadS (int iCanIdent, double dVelGearRadS) |
| |
| bool | shutdownPltf () |
| |
| bool | startWatchdog (bool bStarted) |
| |
| | ~CanCtrlPltfCOb3 () |
| |
Represents all CAN components on an arbitrary canbus.
Definition at line 43 of file CanCtrlPltfCOb3.h.
◆ MotorCANNode
Specify Cannodes (Identifiers to send velocities to one specific motor) This has to be adapted to the hardware-setup!
| Enumerator |
|---|
| CANNODE_WHEEL1DRIVEMOTOR | |
| CANNODE_WHEEL1STEERMOTOR | |
| CANNODE_WHEEL2DRIVEMOTOR | |
| CANNODE_WHEEL2STEERMOTOR | |
| CANNODE_WHEEL3DRIVEMOTOR | |
| CANNODE_WHEEL3STEERMOTOR | |
| CANNODE_WHEEL4DRIVEMOTOR | |
| CANNODE_WHEEL4STEERMOTOR | |
Definition at line 66 of file CanCtrlPltfCOb3.h.
◆ CanCtrlPltfCOb3()
| CanCtrlPltfCOb3::CanCtrlPltfCOb3 |
( |
std::string |
iniDirectory | ) |
|
◆ ~CanCtrlPltfCOb3()
| CanCtrlPltfCOb3::~CanCtrlPltfCOb3 |
( |
| ) |
|
◆ ElmoRecordings()
| int CanCtrlPltfCOb3::ElmoRecordings |
( |
int |
iFlag, |
|
|
int |
iParam, |
|
|
std::string |
sString |
|
) |
| |
Provides several functions for drive information recording purposes using the built in ElmoRecorder, which allows to record drive information at a high frequency.
- Parameters
-
| 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 99: Abort and clear current SDO readout process 100: Request status of readout. Gives back 0 if all transmissions have finished and no CAN polling is needed anymore. |
- Returns
- -1: Unknown flag set; 0: Success; 1: Recorder hasn't been configured yet; 2: data collection still in progress
Definition at line 1456 of file CanCtrlPltfCOb3.cpp.
◆ evalCanBuffer()
| int CanCtrlPltfCOb3::evalCanBuffer |
( |
| ) |
|
◆ getGearDeltaPosVelRadS()
| int CanCtrlPltfCOb3::getGearDeltaPosVelRadS |
( |
int |
iCanIdent, |
|
|
double * |
pdDeltaAngleGearRad, |
|
|
double * |
pdVelGearRadS |
|
) |
| |
Gets the delta joint-angle since the last call and the velocity.
- Parameters
-
| iCanIdent | choose a can node |
| pdDeltaAngleGearRad | delta joint-position since the last call in radian |
| pdVelGearRadS | joint-velocity in radian per second |
Definition at line 1368 of file CanCtrlPltfCOb3.cpp.
◆ getGearPosVelRadS()
| int CanCtrlPltfCOb3::getGearPosVelRadS |
( |
int |
iCanIdent, |
|
|
double * |
pdAngleGearRad, |
|
|
double * |
pdVelGearRadS |
|
) |
| |
Gets the position and velocity.
- Parameters
-
| iCanIdent | choose a can node |
| pdAngleGearRad | joint-position in radian |
| pdVelGearRadS | joint-velocity in radian per second |
Definition at line 1348 of file CanCtrlPltfCOb3.cpp.
◆ getMotorTorque()
| void CanCtrlPltfCOb3::getMotorTorque |
( |
int |
iCanIdent, |
|
|
double * |
pdTorqueNm |
|
) |
| |
Gets the motor torque (calculated from motor active current).
- Parameters
-
| iCanIdent | choose a can node |
| pdTorqueNm | motor-torque in Newtonmeter |
Definition at line 1419 of file CanCtrlPltfCOb3.cpp.
◆ getStatus()
| void CanCtrlPltfCOb3::getStatus |
( |
int |
iCanIdent, |
|
|
int * |
piStatus, |
|
|
int * |
piTempCel |
|
) |
| |
◆ initPltf()
| bool CanCtrlPltfCOb3::initPltf |
( |
| ) |
|
Initializes all CAN nodes of the platfrom and performs homing procedure. !! The homing routine is hardware-dependent (steering and driving is coupled) !! !! If you use this code on other hardware -> make sure te remove or adapt homing sequence !!
Definition at line 893 of file CanCtrlPltfCOb3.cpp.
◆ isPltfError()
| bool CanCtrlPltfCOb3::isPltfError |
( |
| ) |
|
Signs an error of the platform.
- Returns
- true if there is an error.
Definition at line 1204 of file CanCtrlPltfCOb3.cpp.
◆ readConfiguration()
| void CanCtrlPltfCOb3::readConfiguration |
( |
| ) |
|
|
protected |
◆ requestDriveStatus()
| void CanCtrlPltfCOb3::requestDriveStatus |
( |
| ) |
|
Requests the status of the drive. Status-Msg includes whether motor is in error-state (with source, e.g. undercurrent, overheated) or operational (enabled/disabled, at its limits, ...)
Definition at line 1335 of file CanCtrlPltfCOb3.cpp.
◆ requestMotorTorque()
| void CanCtrlPltfCOb3::requestMotorTorque |
( |
| ) |
|
Requests motor-torque (in fact active current) of the drive.
- Parameters
-
| iCanIdent | choose a can node |
Definition at line 1406 of file CanCtrlPltfCOb3.cpp.
◆ requestMotPosVel()
| int CanCtrlPltfCOb3::requestMotPosVel |
( |
int |
iCanIdent | ) |
|
Requests position and velocity of the drive. (This is not implemented for CanDriveHarmonica. sending an Velocity command to an ELMO Harmonica-Ctrl triggers a aswer transmitting the current velocity)
- Parameters
-
| iCanIdent | choose a can node |
Definition at line 1316 of file CanCtrlPltfCOb3.cpp.
◆ resetPltf()
| bool CanCtrlPltfCOb3::resetPltf |
( |
| ) |
|
Reinitializes the nodes on the bus. The function might be neccessary after an emergency stop or an hardware failure to reinit drives.
Definition at line 1169 of file CanCtrlPltfCOb3.cpp.
◆ sendNetStartCanOpen()
| void CanCtrlPltfCOb3::sendNetStartCanOpen |
( |
| ) |
|
|
protected |
◆ setMotorTorque()
| void CanCtrlPltfCOb3::setMotorTorque |
( |
int |
iCanIdent, |
|
|
double |
dTorqueNm |
|
) |
| |
Sends torques to the can node. Status is requested, too.
- Parameters
-
| iCanIdent | choose a can node |
| dTorqueNM | motor-torque in Newtonmeter |
Definition at line 1435 of file CanCtrlPltfCOb3.cpp.
◆ setVelGearRadS()
| int CanCtrlPltfCOb3::setVelGearRadS |
( |
int |
iCanIdent, |
|
|
double |
dVelGearRadS |
|
) |
| |
Sends veolocities to the can node. Status is requested, too.
- Parameters
-
| iCanIdent | choose a can node |
| dVelGearRadS | joint-velocity in radian per second |
Definition at line 1289 of file CanCtrlPltfCOb3.cpp.
◆ shutdownPltf()
| bool CanCtrlPltfCOb3::shutdownPltf |
( |
| ) |
|
Shutdown of the platform. Disables motors, enables brake and disconnects.
Definition at line 1192 of file CanCtrlPltfCOb3.cpp.
◆ startWatchdog()
| bool CanCtrlPltfCOb3::startWatchdog |
( |
bool |
bStarted | ) |
|
◆ m_bWatchdogErr
| bool CanCtrlPltfCOb3::m_bWatchdogErr |
|
protected |
◆ m_CanMsgRec
| CanMsg CanCtrlPltfCOb3::m_CanMsgRec |
|
protected |
◆ m_CanOpenIDParam
◆ m_GearMotDrive1
◆ m_GearMotDrive2
◆ m_GearMotDrive3
◆ m_GearMotDrive4
◆ m_GearMotSteer1
◆ m_GearMotSteer2
◆ m_GearMotSteer3
◆ m_GearMotSteer4
◆ m_IniFile
◆ m_iNumDrives
| int CanCtrlPltfCOb3::m_iNumDrives |
|
protected |
◆ m_iNumMotors
| int CanCtrlPltfCOb3::m_iNumMotors |
|
protected |
◆ m_Mutex
| Mutex CanCtrlPltfCOb3::m_Mutex |
|
protected |
◆ m_Param
◆ m_pCanCtrl
| CanItf* CanCtrlPltfCOb3::m_pCanCtrl |
|
protected |
◆ m_viMotorID
| std::vector<int> CanCtrlPltfCOb3::m_viMotorID |
|
protected |
◆ m_vpMotor
◆ sComposed
| std::string CanCtrlPltfCOb3::sComposed |
|
protected |
◆ sIniDirectory
| std::string CanCtrlPltfCOb3::sIniDirectory |
|
protected |
Reads configuration of can node and components from Inifile (should be adapted to use ROS-Parameter file)
Definition at line 218 of file CanCtrlPltfCOb3.h.
The documentation for this class was generated from the following files: