Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
CanCtrlPltfCOb3 Class Reference

#include <CanCtrlPltfCOb3.h>

List of all members.

Classes

struct  CanNeoIDType
struct  CanOpenIDType
struct  GearMotorParamType
struct  ParamType

Public Types

enum  MotorCANNode {
  CANNODE_WHEEL1DRIVEMOTOR, CANNODE_WHEEL1STEERMOTOR, CANNODE_WHEEL2DRIVEMOTOR, CANNODE_WHEEL2STEERMOTOR,
  CANNODE_WHEEL3DRIVEMOTOR, CANNODE_WHEEL3STEERMOTOR, CANNODE_WHEEL4DRIVEMOTOR, CANNODE_WHEEL4STEERMOTOR
}

Public Member Functions

 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 ()

Protected Member Functions

void readConfiguration ()
void sendNetStartCanOpen ()

Protected Attributes

bool m_bWatchdogErr
CanMsg m_CanMsgRec
CanOpenIDType m_CanOpenIDParam
GearMotorParamType m_GearMotDrive1
GearMotorParamType m_GearMotDrive2
GearMotorParamType m_GearMotDrive3
GearMotorParamType m_GearMotDrive4
GearMotorParamType m_GearMotSteer1
GearMotorParamType m_GearMotSteer2
GearMotorParamType m_GearMotSteer3
GearMotorParamType m_GearMotSteer4
IniFile m_IniFile
int m_iNumDrives
int m_iNumMotors
Mutex m_Mutex
ParamType m_Param
CanItfm_pCanCtrl
std::vector< int > m_viMotorID
std::vector< CanDriveItf * > m_vpMotor
std::string sComposed
std::string sIniDirectory

Detailed Description

Represents all CAN components on an arbitrary canbus.

Definition at line 43 of file CanCtrlPltfCOb3.h.


Member Enumeration Documentation

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.


Constructor & Destructor Documentation

CanCtrlPltfCOb3::CanCtrlPltfCOb3 ( std::string  iniDirectory)

Default constructor.

Definition at line 32 of file CanCtrlPltfCOb3.cpp.

Default destructor.

Definition at line 188 of file CanCtrlPltfCOb3.cpp.


Member Function Documentation

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:
iFlagTo 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.

Triggers evaluation of the can-buffer.

Definition at line 862 of file CanCtrlPltfCOb3.cpp.

int CanCtrlPltfCOb3::getGearDeltaPosVelRadS ( int  iCanIdent,
double *  pdDeltaAngleGearRad,
double *  pdVelGearRadS 
)

Gets the delta joint-angle since the last call and the velocity.

Parameters:
iCanIdentchoose a can node
pdDeltaAngleGearRaddelta joint-position since the last call in radian
pdVelGearRadSjoint-velocity in radian per second

Definition at line 1368 of file CanCtrlPltfCOb3.cpp.

int CanCtrlPltfCOb3::getGearPosVelRadS ( int  iCanIdent,
double *  pdAngleGearRad,
double *  pdVelGearRadS 
)

Gets the position and velocity.

Parameters:
iCanIdentchoose a can node
pdAngleGearRadjoint-position in radian
pdVelGearRadSjoint-velocity in radian per second

Definition at line 1348 of file CanCtrlPltfCOb3.cpp.

void CanCtrlPltfCOb3::getMotorTorque ( int  iCanIdent,
double *  pdTorqueNm 
)

Gets the motor torque (calculated from motor active current).

Parameters:
iCanIdentchoose a can node
pdTorqueNmmotor-torque in Newtonmeter

Definition at line 1419 of file CanCtrlPltfCOb3.cpp.

void CanCtrlPltfCOb3::getStatus ( int  iCanIdent,
int *  piStatus,
int *  piTempCel 
)

Gets the status and temperature in degree celcius. (Not implemented for CanDriveHarmonica)

Parameters:
iCanIdentchoose a CANNode enumatraion

Definition at line 1389 of file CanCtrlPltfCOb3.cpp.

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.

Signs an error of the platform.

Returns:
true if there is an error.

Definition at line 1204 of file CanCtrlPltfCOb3.cpp.

void CanCtrlPltfCOb3::readConfiguration ( ) [protected]

Definition at line 207 of file CanCtrlPltfCOb3.cpp.

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.

Requests motor-torque (in fact active current) of the drive.

Parameters:
iCanIdentchoose a can node

Definition at line 1406 of file CanCtrlPltfCOb3.cpp.

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:
iCanIdentchoose a can node

Definition at line 1316 of file CanCtrlPltfCOb3.cpp.

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.

Starts up can node

Definition at line 1270 of file CanCtrlPltfCOb3.cpp.

void CanCtrlPltfCOb3::setMotorTorque ( int  iCanIdent,
double  dTorqueNm 
)

Sends torques to the can node. Status is requested, too.

Parameters:
iCanIdentchoose a can node
dTorqueNMmotor-torque in Newtonmeter

Definition at line 1435 of file CanCtrlPltfCOb3.cpp.

int CanCtrlPltfCOb3::setVelGearRadS ( int  iCanIdent,
double  dVelGearRadS 
)

Sends veolocities to the can node. Status is requested, too.

Parameters:
iCanIdentchoose a can node
dVelGearRadSjoint-velocity in radian per second

Definition at line 1289 of file CanCtrlPltfCOb3.cpp.

Shutdown of the platform. Disables motors, enables brake and disconnects.

Definition at line 1192 of file CanCtrlPltfCOb3.cpp.

bool CanCtrlPltfCOb3::startWatchdog ( bool  bStarted)

Starts the watchdog of the CAN components.

Definition at line 1256 of file CanCtrlPltfCOb3.cpp.


Member Data Documentation

Definition at line 403 of file CanCtrlPltfCOb3.h.

Definition at line 401 of file CanCtrlPltfCOb3.h.

Definition at line 388 of file CanCtrlPltfCOb3.h.

Definition at line 391 of file CanCtrlPltfCOb3.h.

Definition at line 392 of file CanCtrlPltfCOb3.h.

Definition at line 393 of file CanCtrlPltfCOb3.h.

Definition at line 394 of file CanCtrlPltfCOb3.h.

Definition at line 395 of file CanCtrlPltfCOb3.h.

Definition at line 396 of file CanCtrlPltfCOb3.h.

Definition at line 397 of file CanCtrlPltfCOb3.h.

Definition at line 398 of file CanCtrlPltfCOb3.h.

Definition at line 408 of file CanCtrlPltfCOb3.h.

Definition at line 411 of file CanCtrlPltfCOb3.h.

Definition at line 410 of file CanCtrlPltfCOb3.h.

Definition at line 402 of file CanCtrlPltfCOb3.h.

Definition at line 386 of file CanCtrlPltfCOb3.h.

Definition at line 407 of file CanCtrlPltfCOb3.h.

std::vector<int> CanCtrlPltfCOb3::m_viMotorID [protected]

Definition at line 426 of file CanCtrlPltfCOb3.h.

std::vector<CanDriveItf*> CanCtrlPltfCOb3::m_vpMotor [protected]

Definition at line 423 of file CanCtrlPltfCOb3.h.

std::string CanCtrlPltfCOb3::sComposed [protected]

Definition at line 219 of file CanCtrlPltfCOb3.h.

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:


cob_base_drive_chain
Author(s): Christian Connette
autogenerated on Sat Jun 8 2019 21:02:29