Fast Research Interface Library  Manual and Documentation
Public Types | Public Member Functions | Protected Types | Protected Member Functions | Static Protected Member Functions | Protected Attributes
FastResearchInterface Class Reference

Provides easy access to all functionalities of Fast Research Interface of the KUKA Light-Weight Robot IV More...

#include <FastResearchInterface.h>

List of all members.

Public Types

enum  LWRControlModes { JOINT_POSITION_CONTROL = 10, CART_IMPEDANCE_CONTROL = 20, JOINT_IMPEDANCE_CONTROL = 30 }
 Available control schemes for the KUKA Light-Weight Robot IV. More...

Public Member Functions

 FastResearchInterface (const char *InitFileName)
 Constructor.
 ~FastResearchInterface (void)
 Destructor.
int StartRobot (const unsigned int &ControlMode, const float &TimeOutValueInSeconds=120.0)
 Starts the robot.
int StopRobot (void)
 Stops the robot.
void GetMeasuredJointPositions (float *MeasuredJointPositions)
 Reads the measured joint position vector from the latest data telegram of the KRC unit.
void GetCommandedJointPositions (float *CommandedJointPositions)
 Reads the commanded joint position vector from the latest data telegram of the KRC unit.
void GetCommandedJointPositionOffsets (float *CommandedJointPositionOffsets)
 Reads the commanded joint position offset vector from the latest data telegram of the KRC unit.
void GetMeasuredJointTorques (float *MeasuredJointTorques)
 Reads the measured joint torque vector from the latest data telegram of the KRC unit.
void GetEstimatedExternalJointTorques (float *EstimatedExternalJointTorques)
 Reads the estimated external joint torque vector from the latest data telegram of the KRC unit.
void GetMeasuredCartPose (float *MeasuredCartPose)
 Reads the measured Cartesian pose frame from the latest data telegram of the KRC unit.
void GetCommandedCartPose (float *CommandedCartPose)
 Reads the commanded Cartesian pose frame from the latest data telegram of the KRC unit.
void GetCommandedCartPoseOffsets (float *CommandedCartPoseOffsets)
 Reads the commanded Cartesian pose offset frame from the latest data telegram of the KRC unit.
void GetEstimatedExternalCartForcesAndTorques (float *EstimatedExternalCartForcesAndTorques)
 Reads the estimated external force and torque values w.r.t. the tool frame from the latest data telegram of the KRC unit.
void SetCommandedJointPositions (const float *CommandedJointPositions)
 Copies the desired joint position vector into the data telegram to be send to the KRC unit.
void SetCommandedJointTorques (const float *CommandedJointTorques)
 Copies the desired joint torque vector into the data telegram to be send to the KRC unit.
void SetCommandedJointStiffness (const float *CommandedJointStiffness)
 Copies the desired joint stiffness vector into the data telegram to be send to the KRC unit.
void SetCommandedJointDamping (const float *CommandedJointDamping)
 Copies the desired joint damping vector into the data telegram to be send to the KRC unit.
void SetCommandedCartPose (const float *CommandedCartPose)
 Copies the desired Cartesian pose frame into the data telegram to be send to the KRC unit.
void SetCommandedCartForcesAndTorques (const float *CartForcesAndTorques)
 Copies the desired Cartesian force/torque vector into the data telegram to be send to the KRC unit.
void SetCommandedCartStiffness (const float *CommandedCartStiffness)
 Copies the desired Cartesian stiffness vector into the data telegram to be send to the KRC unit.
void SetCommandedCartDamping (const float *CommandedCartDamping)
 Copies the desired Cartesian damping vector into the data telegram to be send to the KRC unit.
unsigned int GetFRIMode (void)
 Returns the current mode of the Fast Research Interface Running on the KRC unit.
unsigned int GetCurrentControlScheme (void)
 Returns the current control scheme of the Fast Research Interface Running on the KRC unit.
bool IsRobotArmPowerOn (void)
 Returns a Boolean value indicating whether the arm power is turned on and the brakes are released (read from the latest data telegram of the KRC unit)
bool DoesAnyDriveSignalAnError (void)
 Returns a Boolean value indicating whether any drive signals an error (read from the latest data telegram of the KRC unit)
bool DoesAnyDriveSignalAWarning (void)
 Returns a Boolean value indicating whether any drive signals a warning (read from the latest data telegram of the KRC unit)
void GetDriveTemperatures (float *Temperatures)
 Reads the measured drive temperatures for each drive from the latest data telegram of the KRC unit.
void GetCurrentJacobianMatrix (float **JacobianMatrix)
 Reads current Jacobian from the latest data telegram of the KRC unit.
void GetCurrentMassMatrix (float **MassMatrix)
 Reads current mass matrix from the latest data telegram of the KRC unit.
void GetCurrentGravityVector (float *GravityVector)
 Reads current gravity vector from the latest data telegram of the KRC unit.
float GetFRICycleTime (void)
 Returns the communication cycle time between the KRC unit and the remote host (read from the latest data telegram of the KRC unit)
int GetCommunicationTimingQuality (void)
 Returns the current communication quality measured by the KRC unit (read from the latest data telegram of the KRC unit)
float GetUDPAnswerRate (void)
 Returns the current answer rate of the remote host measured by the KRC unit (read from the latest data telegram of the KRC unit)
float GetUDPLatencyInSeconds (void)
 Returns the current communication latency measured by the KRC unit (read from the latest data telegram of the KRC unit)
float GetUDPJitterInSeconds (void)
 Returns the current communication jitter measured by the KRC unit (read from the latest data telegram of the KRC unit)
float GetUDPPackageLossRate (void)
 Returns the current data package loss rate measured by the KRC unit (read from the latest data telegram of the KRC unit)
unsigned int GetNumberOfMissedUDPPackages (void)
 Returns the number of lost data packages measured by the KRC unit (read from the latest data telegram of the KRC unit)
unsigned int GetValueOfKRCSequenceCounter (void)
 Returns the current value of the data telegram sequence counter of the KRC unit (read from the latest data telegram of the KRC unit)
void GetKRLBoolValues (bool *KRLBoolValues)
 Gets the current value of $FRI_TO_BOOL[] as set by the KRL program (read from the latest data telegram of the KRC unit)
void GetKRLIntValues (int *KRLIntValues)
 Gets the current value of $FRI_TO_INT[] as set by the KRL program (read from the latest data telegram of the KRC unit)
void GetKRLFloatValues (float *KRLFloatValues)
 Gets the current value of $FRI_TO_REAL[] as set by the KRL program (read from the latest data telegram of the KRC unit)
bool GetKRLBoolValue (const unsigned int &Index)
 Returns one single element of the KRL array $FRI_TO_BOOL[] (read from the latest data telegram of the KRC unit)
int GetKRLIntValue (const unsigned int &Index)
 Returns one single element of the KRL array $FRI_TO_INT[] (read from the latest data telegram of the KRC unit)
float GetKRLFloatValue (const unsigned int &Index)
 Returns one single element of the KRL array $FRI_TO_REAL[] (read from the latest data telegram of the KRC unit)
void SetKRLBoolValues (const bool *KRLBoolValues)
 Copies data into the data telegram to be send to the KRC unit and read by the KRL program from the array $FRI_FRM_BOOL[]
void SetKRLIntValues (const int *KRLIntValues)
 Copies data into the data telegram to be send to the KRC unit and read by the KRL program from the array $FRI_FRM_INT[]
void SetKRLFloatValues (const float *KRLFloatValues)
 Copies data into the data telegram to be send to the KRC unit and read by the KRL program from the array $FRI_FRM_REAL[]
void SetKRLBoolValue (const unsigned int &Index, const bool &Value)
 Copies one single Boolean value into the data telegram to be send to the KRC unit and read by the KRL program from the $FRI_FRM_BOOL[Index]
void SetKRLIntValue (const unsigned int &Index, const int &Value)
 Copies one single integer value into the data telegram to be send to the KRC unit and read by the KRL program from the $FRI_FRM_INT[Index]
void SetKRLFloatValue (const unsigned int &Index, const float &Value)
 Copies one single floating point value into the data telegram to be send to the KRC unit and read by the KRL program from the $FRI_FRM_REAL[Index]
int WaitForKRCTick (const unsigned int &TimeoutValueInMicroSeconds=0)
 Blocks the calling thread until a message from the KRC unit has been received.
int WaitForTimerTick (const unsigned int &TimeoutValueInMicroSeconds=0)
 Blocks the calling thread until the timer thread sends a signal.
bool IsMachineOK (void)
 Returns a Boolean value indicating whether the robot is ready for operation.
const char * GetCompleteRobotStateAndInformation (void)
 Returns a pointer to an array of char values describing the complete state of the robot.
int printf (const char *Format,...)
 A real-time wrapper for printf.
int PrepareLogging (const char *FileIdentifier=NULL)
 Creates and prepares an output file for logging.
int StartLogging (void)
 Starts real-time data logging.
int StopLogging (void)
 Stops real-time data logging.
int WriteLoggingDataFile (void)
 Writes logged data to the output file and closes the file.

Protected Types

enum  CalledLoggingMethod { PrepareLoggingCalled = 1, StartLoggingCalled = 2, StopLoggingCalled = 3, WriteLoggingDataFileCalled = 4 }
 Describes the state of the data logger. More...

Protected Member Functions

int ReadInitFile (const char *InitFileName)
 Reads the initialization file.
int SetControlScheme (const unsigned int &ControlScheme)
 Prepares a part of the robot start-up procedure.

Static Protected Member Functions

static void * TimerThreadMain (void *ThreadArgument)
 Thread function for the timer thread.
static void * KRCCommunicationThreadMain (void *ThreadArgument)

Protected Attributes

bool TerminateTimerThread
 Used as indication for the timer thread to terminate itself.
bool TimerFlag
 Set by the timer thread each time its timer fires.
bool TerminateKRCCommunicationThread
 Flag to terminate the communication thread.
bool NewDataFromKRCReceived
 Used as indication for the KRC communication thread to terminate itself.
bool LoggingIsActive
 Used by FastResearchInterface::StartLogging() and FastResearchInterface::StopLogging()
bool ThreadCreated
 Used during the creation of new threads to acknowledge the creating thread that the new thread is running.
CalledLoggingMethod LoggingState
 Stores which logging methods has been called lately.
char * RobotName
 A pointer to an array of char values containing the name of the robot (specified in the initialization file)
char * LoggingPath
 A pointer to an array of char values containing the path of the log file (specified in the initialization file)
char * LoggingFileName
 A pointer to an array of char values containing the name of the log file (specified in the initialization file)
char * RobotStateString
 A pointer to an array of char values containing the description of the complete robot state.
unsigned int CurrentControlScheme
 Contains the current control scheme.
unsigned int NumberOfLoggingFileEntries
 Contains the maximum number of logging file entries (specified in the initialization file)
unsigned int PriorityKRCCommunicationThread
 Contains the priority of the KRC communication thread (specified in the initialization file)
unsigned int PriorityTimerThread
 Contains the priority of the timer thread (specified in the initialization file)
unsigned int PriorityMainThread
 Contains the priority of the thread that called the constructor (specified in the initialization file)
unsigned int PriorityOutputConsoleThread
 Contains the priority of the output thread (specified in the initialization file)
double CycleTime
 Contains the cycle time in seconds (specified in the initialization file)
pthread_mutex_t MutexForControlData
 Mutex to protect FastResearchInterface::ReadData and FastResearchInterface::CommandData.
pthread_mutex_t MutexForCondVarForTimer
 Mutex to protect FastResearchInterface::TimerFlag.
pthread_mutex_t MutexForLogging
 Mutex to protect FastResearchInterface::LoggingIsActive.
pthread_mutex_t MutexForThreadCreation
 Mutex used during the creation of new threads.
pthread_cond_t CondVarForTimer
 Condition variable used by the timer thread FastResearchInterface::TimerThreadMain() for broadcasting after the firing of its timer.
pthread_cond_t CondVarForDataReceptionFromKRC
 Condition variable used by the KRC communication thread FastResearchInterface::KRCCommunicationThreadMain() for broadcasting after the reception of a message from the KRC unit.
pthread_cond_t CondVarForThreadCreation
 Condition variable used during the creation of new threads.
pthread_t KRCCommunicationThread
 POSIX thread identifier for the KRC communication thread FastResearchInterface::KRCCommunicationThreadMain()
pthread_t TimerThread
 POSIX thread identifier for the timer thread FastResearchInterface::TimerThreadMain()
pthread_t MainThread
 POSIX thread identifier for the thread calling the constructor FastResearchInterface::FastResearchInterface()
ConsoleOutputConsole
 Pointer to a Console object used for message output through a low-priority thread.
DataLoggingDataLogger
 Pointer to a DataLogging object used for real-time logging of low-level control data.
tFriMsrData ReadData
 Data structure object containing a copy of a complete received data telegram from the KRC unit.
tFriCmdData CommandData
 Data structure object containing a copy of a complete data telegram to be sent to the KRC unit.

Detailed Description

Provides easy access to all functionalities of Fast Research Interface of the KUKA Light-Weight Robot IV

This is the main class of the Fast Research Interface Library for the KUKA Light-Weight Robot IV. An object of this class provides the following functionalities:

Users may use this class as the interface to the KRC unit if the complete functionality is required for the desired application. In order to provide a simple and easy-to-start-with interface, this class is used by (but not derived to) the classes

which are all derived from the class LWRBaseControllerInterface.

Attention:
Only one object of this class is supposed to be created on a remote host. Otherwise indeterministic behavior may occur.
Remarks:
For a general description of the Fast Research Interface Library, please refer to the Introduction.
See also:
LWRBaseControllerInterface
LWRJointPositionController
LWRCartImpedanceController
LWRJointImpedanceController

Definition at line 118 of file FastResearchInterface.h.


Member Enumeration Documentation

Describes the state of the data logger.

See also:
FastResearchInterface::PrepareLogging() (not real-time capable)
FastResearchInterface::StartLogging() (real-time capable)
FastResearchInterface::StopLogging() (real-time capable)
FastResearchInterface::WriteLoggingDataFile() (not real-time capable)
Enumerator:
PrepareLoggingCalled 
StartLoggingCalled 
StopLoggingCalled 
WriteLoggingDataFileCalled 

Definition at line 1612 of file FastResearchInterface.h.

Available control schemes for the KUKA Light-Weight Robot IV.

Depending the parameter ControlMode of the method FastResearchInterface::StartRobot(), the KRL program (cf.KRL File: FRIControl.src) sets the global variable $stiffness.strategy and calls the KRL function friStart().

Enumerator:
JOINT_POSITION_CONTROL 

Joint position control.

CART_IMPEDANCE_CONTROL 

Cartesian impedance control.

JOINT_IMPEDANCE_CONTROL 

Joint impedance control.

Definition at line 211 of file FastResearchInterface.h.


Constructor & Destructor Documentation

FastResearchInterface::FastResearchInterface ( const char *  InitFileName)

Constructor.

This constructor performs several procedures. It

In case,

the constructor lets the calling process terminate and exits with a value of EXIT_FAILURE.

Parameters:
InitFileNameA pointer to an array of char values containing the path and filename of the initialization file (e.g., "/home/lwrcontrol/etc/980039-FRI-Driver.init"). For details about this file, please refer to The Initialization File for the Fast Research Interface Library.
Note:
All threads of this class, that is,

use the Fifo scheduling policy (SCHED_FIFO).
Attention:
The call of the constructor does not fulfill any real-time requirements.

Definition at line 78 of file FastResearchInterface.cpp.

Destructor.

This destructor performs a set of procedures to cleanly shutdown the robot:

Attention:
The call of the destructor does not fulfill any real-time requirements.

Definition at line 262 of file FastResearchInterface.cpp.


Member Function Documentation

Returns a Boolean value indicating whether any drive signals an error (read from the latest data telegram of the KRC unit)

Returns:
  • true if one are more drives signal an error
  • false otherwise
See also:
friComm.h
tFriMsrData

Definition at line 122 of file GetRobotStatusData.cpp.

Returns a Boolean value indicating whether any drive signals a warning (read from the latest data telegram of the KRC unit)

Returns:
  • true if one are more drives signal a warning
  • false otherwise
See also:
friComm.h
tFriMsrData

Definition at line 137 of file GetRobotStatusData.cpp.

void FastResearchInterface::GetCommandedCartPose ( float *  CommandedCartPose)

Reads the commanded Cartesian pose frame from the latest data telegram of the KRC unit.

Parameters:
CommandedCartPoseA pointer to an array of float values; the array has to have at least a size of twelve elements. The commanded Cartesian pose frame is written into this array.
See also:
tFriMsrData

Definition at line 173 of file GetRobotControlData.cpp.

void FastResearchInterface::GetCommandedCartPoseOffsets ( float *  CommandedCartPoseOffsets)

Reads the commanded Cartesian pose offset frame from the latest data telegram of the KRC unit.

Parameters:
CommandedCartPoseOffsetsA pointer to an array of float values; the array has to have at least a size of twelve elements. The commanded Cartesian pose offset frame is written into this array.
See also:
tFriMsrData

Definition at line 191 of file GetRobotControlData.cpp.

void FastResearchInterface::GetCommandedJointPositionOffsets ( float *  CommandedJointPositionOffsets)

Reads the commanded joint position offset vector from the latest data telegram of the KRC unit.

Parameters:
CommandedJointPositionOffsetsA pointer to an array of float values; the array has to have at least a size of seven elements. The commanded joint position offset is written into this array.
See also:
tFriMsrData

Definition at line 101 of file GetRobotControlData.cpp.

void FastResearchInterface::GetCommandedJointPositions ( float *  CommandedJointPositions)

Reads the commanded joint position vector from the latest data telegram of the KRC unit.

Parameters:
CommandedJointPositionsA pointer to an array of float values; the array has to have at least a size of seven elements. The commanded joint position vector is written into this array.
See also:
tFriMsrData

Definition at line 83 of file GetRobotControlData.cpp.

Returns the current communication quality measured by the KRC unit (read from the latest data telegram of the KRC unit)

Returns:
  • FRI_QUALITY_UNACCEPTABLE
  • FRI_QUALITY_BAD
  • FRI_QUALITY_OK
  • FRI_QUALITY_PERFECT
See also:
friComm.h
tFriMsrData

Definition at line 80 of file GetUDPCommunicationData.cpp.

Returns a pointer to an array of char values describing the complete state of the robot.

This method summarizes the all available robot information in a simple C-string.

Returns:
A pointer to an array of char values describing the complete state of the robot
See also:
tFriMsrData
GetCompleteRobotStateAndInformation.cpp

Definition at line 73 of file GetCompleteRobotStateAndInformation.cpp.

Returns the current control scheme of the Fast Research Interface Running on the KRC unit.

(read from the latest data telegram of the KRC unit)

Returns:
See also:
friComm.h
tFriMsrData

Definition at line 79 of file GetRobotStatusData.cpp.

void FastResearchInterface::GetCurrentGravityVector ( float *  GravityVector)

Reads current gravity vector from the latest data telegram of the KRC unit.

Parameters:
GravityVectorA pointer to an two-dimensional array of float values the array has to have at least a size of 49 elements. The current gravity vector is written into this array.
Warning:
This method has never been tested.
Todo:
Test this method!
See also:
tFriMsrData

Definition at line 314 of file GetRobotStatusData.cpp.

void FastResearchInterface::GetCurrentJacobianMatrix ( float **  JacobianMatrix)

Reads current Jacobian from the latest data telegram of the KRC unit.

Parameters:
JacobianMatrixA pointer to an two-dimensional array of float values the array has to have at least a size of 42 elements. The current Jacobian matrix is written into this array.
Warning:
This method has never been tested.
Todo:
Test this method!
See also:
tFriMsrData

Definition at line 269 of file GetRobotStatusData.cpp.

void FastResearchInterface::GetCurrentMassMatrix ( float **  MassMatrix)

Reads current mass matrix from the latest data telegram of the KRC unit.

Parameters:
MassMatrixA pointer to an two-dimensional array of float values the array has to have at least a size of 49 elements. The current mass matrix is written into this array.
Warning:
This method has never been tested.
Todo:
Test this method!
See also:
tFriMsrData

Definition at line 292 of file GetRobotStatusData.cpp.

void FastResearchInterface::GetDriveTemperatures ( float *  Temperatures)

Reads the measured drive temperatures for each drive from the latest data telegram of the KRC unit.

Parameters:
TemperaturesA pointer to an array of float values; the array has to have at least a size of seven elements. The measured drive temperatures for each drive is written into this array.
See also:
tFriMsrData

Definition at line 152 of file GetRobotStatusData.cpp.

void FastResearchInterface::GetEstimatedExternalCartForcesAndTorques ( float *  EstimatedExternalCartForcesAndTorques)

Reads the estimated external force and torque values w.r.t. the tool frame from the latest data telegram of the KRC unit.

Parameters:
EstimatedExternalCartForcesAndTorquesA pointer to an array of float values; the array has to have at least a size of six elements. The estimated external force and torque values are written into this array.
See also:
tFriMsrData

Definition at line 209 of file GetRobotControlData.cpp.

void FastResearchInterface::GetEstimatedExternalJointTorques ( float *  EstimatedExternalJointTorques)

Reads the estimated external joint torque vector from the latest data telegram of the KRC unit.

Parameters:
EstimatedExternalJointTorquesA pointer to an array of float values; the array has to have at least a size of seven elements. The estimated external joint torque vector is written into this array.
See also:
tFriMsrData

Definition at line 137 of file GetRobotControlData.cpp.

Returns the communication cycle time between the KRC unit and the remote host (read from the latest data telegram of the KRC unit)

Returns:
Communication cycle time in seconds.
See also:
tFriMsrData

Definition at line 65 of file GetUDPCommunicationData.cpp.

unsigned int FastResearchInterface::GetFRIMode ( void  )

Returns the current mode of the Fast Research Interface Running on the KRC unit.

(read from the latest data telegram of the KRC unit)

Returns:
  • FRI_STATE_OFF off (i.e., no UDP connection has been established yet)
  • FRI_STATE_MON monitor mode
  • FRI_STATE_CMD command mode
See also:
friComm.h
tFriMsrData

Definition at line 65 of file GetRobotStatusData.cpp.

bool FastResearchInterface::GetKRLBoolValue ( const unsigned int &  Index)

Returns one single element of the KRL array $FRI_TO_BOOL[] (read from the latest data telegram of the KRC unit)

Parameters:
IndexThe index of the desired Boolean value; this value has to be in range 0f 0,...,15
Returns:
The desired bool value at Index
Warning:
This method has never been tested.
Todo:
Test this method!
See also:
tFriMsrData
FastResearchInterface::GetKRLBoolValues()
KRL Source Files

Definition at line 224 of file GetRobotStatusData.cpp.

void FastResearchInterface::GetKRLBoolValues ( bool *  KRLBoolValues)

Gets the current value of $FRI_TO_BOOL[] as set by the KRL program (read from the latest data telegram of the KRC unit)

Parameters:
KRLBoolValuesA pointer to an array of bool values; the array has to have at least a size of 16 elements. The Boolean values set by the KRL program running on the KRC unit are copied into this array.
Warning:
This method has never been tested.
Todo:
Test this method!
See also:
tFriMsrData
FastResearchInterface::GetKRLBoolValue()
FastResearchInterface::SetKRLBoolValues()
KRL Source Files

Definition at line 170 of file GetRobotStatusData.cpp.

bool FastResearchInterface::GetKRLFloatValue ( const unsigned int &  Index)

Returns one single element of the KRL array $FRI_TO_REAL[] (read from the latest data telegram of the KRC unit)

Parameters:
IndexThe index of the desired floating point value; this value has to be in range 0f 0,...,15
Returns:
The desired float value at Index
See also:
tFriMsrData
FastResearchInterface::GetKRLFloatValues()
KRL Source Files

Definition at line 254 of file GetRobotStatusData.cpp.

void FastResearchInterface::GetKRLFloatValues ( float *  KRLFloatValues)

Gets the current value of $FRI_TO_REAL[] as set by the KRL program (read from the latest data telegram of the KRC unit)

Parameters:
KRLFloatValuesA pointer to an array of float values; the array has to have at least a size of 16 elements. The floating point values set by the KRL program running on the KRC unit are copied into this array.
See also:
tFriMsrData
FastResearchInterface::GetKRLFloatValue()
FastResearchInterface::SetKRLFloatValues()
KRL Source Files

Definition at line 206 of file GetRobotStatusData.cpp.

bool FastResearchInterface::GetKRLIntValue ( const unsigned int &  Index)

Returns one single element of the KRL array $FRI_TO_INT[] (read from the latest data telegram of the KRC unit)

Parameters:
IndexThe index of the desired integer value; this value has to be in range 0f 0,...,15
Returns:
The desired int value at Index
See also:
tFriMsrData
FastResearchInterface::GetKRLIntValues()
KRL Source Files

Definition at line 239 of file GetRobotStatusData.cpp.

void FastResearchInterface::GetKRLIntValues ( int *  KRLIntValues)

Gets the current value of $FRI_TO_INT[] as set by the KRL program (read from the latest data telegram of the KRC unit)

Parameters:
KRLIntValuesA pointer to an array of int values; the array has to have at least a size of 16 elements. The integer values set by the KRL program running on the KRC unit are copied into this array.
See also:
tFriMsrData
FastResearchInterface::GetKRLIntValue()
FastResearchInterface::SetKRLIntValues()
KRL Source Files

Definition at line 188 of file GetRobotStatusData.cpp.

void FastResearchInterface::GetMeasuredCartPose ( float *  MeasuredCartPose)

Reads the measured Cartesian pose frame from the latest data telegram of the KRC unit.

Parameters:
MeasuredCartPoseA pointer to an array of float values; the array has to have at least a size of twelve elements. The measured Cartesian pose frame is written into this array.
See also:
tFriMsrData

Definition at line 155 of file GetRobotControlData.cpp.

void FastResearchInterface::GetMeasuredJointPositions ( float *  MeasuredJointPositions)

Reads the measured joint position vector from the latest data telegram of the KRC unit.

Parameters:
MeasuredJointPositionsA pointer to an array of float values; the array has to have at least a size of seven elements. The measured joint position vector is written into this array.
See also:
tFriMsrData

Definition at line 65 of file GetRobotControlData.cpp.

void FastResearchInterface::GetMeasuredJointTorques ( float *  MeasuredJointTorques)

Reads the measured joint torque vector from the latest data telegram of the KRC unit.

Parameters:
MeasuredJointTorquesA pointer to an array of float values; the array has to have at least a size of seven elements. The measured joint torque vector is written into this array.
See also:
tFriMsrData

Definition at line 119 of file GetRobotControlData.cpp.

Returns the number of lost data packages measured by the KRC unit (read from the latest data telegram of the KRC unit)

Returns:
Number of lost data packages
See also:
tFriMsrData

Definition at line 155 of file GetUDPCommunicationData.cpp.

Returns the current answer rate of the remote host measured by the KRC unit (read from the latest data telegram of the KRC unit)

Returns:
Answer rate
See also:
tFriMsrData

Definition at line 95 of file GetUDPCommunicationData.cpp.

Returns the current communication jitter measured by the KRC unit (read from the latest data telegram of the KRC unit)

Returns:
Current communication jitter in seconds
See also:
tFriMsrData

Definition at line 125 of file GetUDPCommunicationData.cpp.

Returns the current communication latency measured by the KRC unit (read from the latest data telegram of the KRC unit)

Returns:
Current communication latency in seconds
See also:
tFriMsrData

Definition at line 110 of file GetUDPCommunicationData.cpp.

Returns the current data package loss rate measured by the KRC unit (read from the latest data telegram of the KRC unit)

Returns:
Current data package loss rate
See also:
tFriMsrData

Definition at line 140 of file GetUDPCommunicationData.cpp.

Returns the current value of the data telegram sequence counter of the KRC unit (read from the latest data telegram of the KRC unit)

Note:
This value may be affected by overflows, if the system runs for more than 49 days without interruption.
Returns:
Current value of the data telegram sequence counter
See also:
tFriMsrData

Definition at line 170 of file GetUDPCommunicationData.cpp.

Returns a Boolean value indicating whether the robot is ready for operation.

This method will return true if the following three conditions are fulfilled:

  • the KRC unit is Command Mode,
  • the robot arm is powered on and the brakes are released, and
  • none of the drives signals an error.
Returns:
  • true if the machine is ready for operation
  • false otherwise
See also:
FastResearchInterface::GetFRIMode()
FastResearchInterface::IsRobotArmPowerOn()
FastResearchInterface::DoesAnyDriveSignalAnError()

Definition at line 332 of file GetRobotStatusData.cpp.

Returns a Boolean value indicating whether the arm power is turned on and the brakes are released (read from the latest data telegram of the KRC unit)

Returns:
  • true if the arm power is on and the brakes are released
  • false if the arm power is off and the brakes are engaged
See also:
friComm.h
tFriMsrData

Definition at line 107 of file GetRobotStatusData.cpp.

void * FastResearchInterface::KRCCommunicationThreadMain ( void *  ThreadArgument) [static, protected]

Definition at line 76 of file KRCCommunicationThreadMain.cpp.

int FastResearchInterface::PrepareLogging ( const char *  FileIdentifier = NULL)

Creates and prepares an output file for logging.

Depending on the controller (cf. FastResearchInterface::CurrentControlScheme) that has been selected during the call of FastResearchInterface::StartRobot(), the method DataLogging::PrepareLogging() is called by this function.

Within the class FastResearchInterface, the data logging methods are supposed to be used in the following order:

  1. This method (not real-time capable)
  2. FastResearchInterface::StartLogging() (real-time capable)
  3. FastResearchInterface::StopLogging() (real-time capable)
  4. FastResearchInterface::WriteLoggingDataFile() (not real-time capable)

After this method has been successfully called, the real-time capable method FastResearchInterface::StartLogging() may be called at any time to start the actual data logging.

Parameters:
FileIdentifierA pointer to an array of char values containing a string to identify the written log file. This parameter is optional.
Returns:
Attention:
The call of this method does not fulfill any real-time requirements.
Remarks:
Please refer to the class DataLogging for more details on real-time data logging for the KUKA Light-Weight-Robot.
See also:
DataLogging::PrepareLogging()

Definition at line 65 of file LoggingMethods.cpp.

int FastResearchInterface::printf ( const char *  Format,
  ... 
)

A real-time wrapper for printf.

This is the main method of the class Console; it may be called by real-time threads of the process to which this object belongs. It copies the formated character string to one part of the double buffer and uses the condition variable Console::CondVar to wake up the low-priority thread Console::ConsoleThreadMain(), which can work on the actual output as soon as it becomes scheduled.

Parameters:
FormatFormats the string to be sent to Console::Handler. For details please refer for example to this page: http://www.qnx.com/developers/docs/6.3.2/neutrino/lib_ref/p/printf.html.
...A variable argument list is used here. For details, please refer to stdarg.h and http://www.qnx.com/developers/docs/6.3.2/neutrino/lib_ref/p/printf.html.
Returns:
  • The number characters sent to the file handler Console::Handler.
  • If the capacity of the double buffer is exceeded, ENOBUFS is returned, and a corresponding string is written to the output in order to acknowledge the user.

Definition at line 358 of file FastResearchInterface.cpp.

int FastResearchInterface::ReadInitFile ( const char *  InitFileName) [protected]

Reads the initialization file.

Parameters:
InitFileNameA pointer to an array of char containing the name of the file that provides the desired initialization values/parameters.
Returns:
  • The number of read parameter
  • -1 if the file specified by InitFileName could not be opened
See also:
InitializationFileEntry

Definition at line 67 of file ReadInitFile.cpp.

void FastResearchInterface::SetCommandedCartDamping ( const float *  CommandedCartDamping)

Copies the desired Cartesian damping vector into the data telegram to be send to the KRC unit.

Parameters:
CommandedCartDampingA pointer to an array of float values; the array has to have at least a size of six elements. The desired Cartesian damping vector is copied from this array.
Note:
This value will only be relevant if the Cartesian impedance controller is active.
See also:
tFriCmdData

Definition at line 191 of file SetRobotControlData.cpp.

void FastResearchInterface::SetCommandedCartForcesAndTorques ( const float *  CartForcesAndTorques)

Copies the desired Cartesian force/torque vector into the data telegram to be send to the KRC unit.

Parameters:
CartForcesAndTorquesA pointer to an array of float values; the array has to have at least a size of six elements. The desired Cartesian force/torque vector is copied from this array.
Note:
This value will only be relevant if the Cartesian impedance controller is active.
See also:
tFriCmdData

Definition at line 155 of file SetRobotControlData.cpp.

void FastResearchInterface::SetCommandedCartPose ( const float *  CommandedCartPose)

Copies the desired Cartesian pose frame into the data telegram to be send to the KRC unit.

Parameters:
CommandedCartPoseA pointer to an array of float values; the array has to have at least a size of twelve elements. The desired Cartesian pose frame is copied from this array.
Note:
This value will only be relevant if the Cartesian impedance controller is active.
See also:
tFriCmdData

Definition at line 137 of file SetRobotControlData.cpp.

void FastResearchInterface::SetCommandedCartStiffness ( const float *  CommandedCartStiffness)

Copies the desired Cartesian stiffness vector into the data telegram to be send to the KRC unit.

Parameters:
CommandedCartStiffnessA pointer to an array of float values; the array has to have at least a size of six elements. The desired Cartesian stiffness vector is copied from this array.
Note:
This value will only be relevant if the Cartesian impedance controller is active.
See also:
tFriCmdData

Definition at line 173 of file SetRobotControlData.cpp.

void FastResearchInterface::SetCommandedJointDamping ( const float *  CommandedJointDamping)

Copies the desired joint damping vector into the data telegram to be send to the KRC unit.

Parameters:
CommandedJointDampingA pointer to an array of float values; the array has to have at least a size of seven elements. The desired joint damping vector is copied from this array.
Note:
This value will only be relevant if the joint impedance controller is active.
See also:
tFriCmdData

Definition at line 119 of file SetRobotControlData.cpp.

void FastResearchInterface::SetCommandedJointPositions ( const float *  CommandedJointPositions)

Copies the desired joint position vector into the data telegram to be send to the KRC unit.

Parameters:
CommandedJointPositionsA pointer to an array of float values; the array has to have at least a size of seven elements. The desired joint position vector (given in radians) is copied from this array.
Note:
This value will only be relevant if the joint position or the joint impedance controller is active.
See also:
tFriCmdData

Definition at line 65 of file SetRobotControlData.cpp.

void FastResearchInterface::SetCommandedJointStiffness ( const float *  CommandedJointStiffness)

Copies the desired joint stiffness vector into the data telegram to be send to the KRC unit.

Parameters:
CommandedJointStiffnessA pointer to an array of float values; the array has to have at least a size of seven elements. The desired joint stiffness vector is copied from this array.
Note:
This value will only be relevant if the joint impedance controller is active.
See also:
tFriCmdData

Definition at line 101 of file SetRobotControlData.cpp.

void FastResearchInterface::SetCommandedJointTorques ( const float *  CommandedJointTorques)

Copies the desired joint torque vector into the data telegram to be send to the KRC unit.

Parameters:
CommandedJointTorquesA pointer to an array of float values; the array has to have at least a size of seven elements. The desired joint torque vector (given in Nm) is copied from this array.
Note:
This value will only be relevant if the joint impedance or the joint torque controller is active.
See also:
tFriCmdData

Definition at line 83 of file SetRobotControlData.cpp.

int FastResearchInterface::SetControlScheme ( const unsigned int &  ControlScheme) [protected]

Prepares a part of the robot start-up procedure.

This method encapsulates a part of the method FastResearchInterface::StartRobot(). It sets controller flags of tFriCmdData and sets up the shared KRL variables used for intercommunication of the Fast Research Library and the KRL program FRIControl (cf.KRL File: FRIControl.src).

Parameters:
ControlSchemeEither value of the enumeration FastResearchInterface::LWRControlModes:

Returns:
  • EINVAL if the value is not an element of LWRControlModes.
  • ENOTCONN if no connection between the remote host and the KRC unit is available,
  • or if the KRC unit does not answer anymore (e.g., due to a manual call of firClose().
  • EBUSY if the KRC unit is already in Command Mode.
  • EOK if no error occurred.
See also:
FastResearchInterface::StartRobot()
tFriCmdData

Definition at line 67 of file SetControlScheme.cpp.

void FastResearchInterface::SetKRLBoolValue ( const unsigned int &  Index,
const bool &  Value 
)

Copies one single Boolean value into the data telegram to be send to the KRC unit and read by the KRL program from the $FRI_FRM_BOOL[Index]

Parameters:
IndexThe index of the commanded Boolean value in the KRL array $FRI_FRM_BOOL[]; this value has to be in range 0f 0,...,15
ValueThe value to be copied into the data telegram and to read by the KRL program as $FRI_FRM_BOOL[Index].
Warning:
This method has never been tested.
Todo:
Test this method!
See also:
tFriCmdData
FastResearchInterface::SetKRLBoolValues()
FastResearchInterface::GetKRLBoolValue()
KRL Source Files

Definition at line 126 of file SetRobotStatusData.cpp.

void FastResearchInterface::SetKRLBoolValues ( const bool *  KRLBoolValues)

Copies data into the data telegram to be send to the KRC unit and read by the KRL program from the array $FRI_FRM_BOOL[]

Parameters:
KRLBoolValuesA pointer to an array of bool values; the array has to have at least a size of 16 elements. The Boolean values are copied into the data telegram.
Warning:
This method has never been tested.
Todo:
Test this method!
See also:
tFriCmdData
FastResearchInterface::SetKRLBoolValue()
FastResearchInterface::GetKRLBoolValues()
KRL Source Files

Definition at line 65 of file SetRobotStatusData.cpp.

void FastResearchInterface::SetKRLFloatValue ( const unsigned int &  Index,
const float &  Value 
)

Copies one single floating point value into the data telegram to be send to the KRC unit and read by the KRL program from the $FRI_FRM_REAL[Index]

Parameters:
IndexThe index of the commanded floating point value in the KRL array $FRI_FRM_REAL[]; this value has to be in range 0f 0,...,15
ValueThe value to be copied into the data telegram and to read by the KRL program as $FRI_FRM_REAL[Index].
See also:
tFriCmdData
FastResearchInterface::SetKRLFloatValues()
FastResearchInterface::GetKRLFloatValue()
KRL Source Files

Definition at line 159 of file SetRobotStatusData.cpp.

void FastResearchInterface::SetKRLFloatValues ( const float *  KRLFloatValues)

Copies data into the data telegram to be send to the KRC unit and read by the KRL program from the array $FRI_FRM_REAL[]

Parameters:
KRLFloatValuesA pointer to an array of float values; the array has to have at least a size of 16 elements. The floating point values are copied into the data telegram.
See also:
tFriCmdData
FastResearchInterface::SetKRLFloatValue()
FastResearchInterface::GetKRLFloatValues()
KRL Source Files

Definition at line 108 of file SetRobotStatusData.cpp.

void FastResearchInterface::SetKRLIntValue ( const unsigned int &  Index,
const int &  Value 
)

Copies one single integer value into the data telegram to be send to the KRC unit and read by the KRL program from the $FRI_FRM_INT[Index]

Parameters:
IndexThe index of the commanded integer value in the KRL array $FRI_FRM_INT[]; this value has to be in range 0f 0,...,15
ValueThe value to be copied into the data telegram and to read by the KRL program as $FRI_FRM_INT[Index].
See also:
tFriCmdData
FastResearchInterface::SetKRLIntValues()
FastResearchInterface::GetKRLIntValue()
KRL Source Files

Definition at line 146 of file SetRobotStatusData.cpp.

void FastResearchInterface::SetKRLIntValues ( const int *  KRLIntValues)

Copies data into the data telegram to be send to the KRC unit and read by the KRL program from the array $FRI_FRM_INT[]

Parameters:
KRLIntValuesA pointer to an array of int values; the array has to have at least a size of 16 elements. The integer values are copied into the data telegram.
See also:
tFriCmdData
FastResearchInterface::SetKRLIntValue()
FastResearchInterface::GetKRLIntValues()
KRL Source Files

Definition at line 90 of file SetRobotStatusData.cpp.

Starts real-time data logging.

A call of this method sets the flag FastResearchInterface::LoggingIsActive, which lets the communication thread FastResearchInterface::KRCCommunicationThreadMain() write all relevant control data into heap memory. After calling FastResearchInterface::StopLogging(), FastResearchInterface::WriteLoggingDataFile() can be called, which finally writes all logged data into a file.

This method can only be called if FastResearchInterface::PrepareLogging() was called beforehand.

Within the class FastResearchInterface, the data logging methods are supposed to be used in the following order:

  1. FastResearchInterface::PrepareLogging() (not real-time capable)
  2. This method (real-time capable)
  3. FastResearchInterface::StopLogging() (real-time capable)
  4. FastResearchInterface::WriteLoggingDataFile() (not real-time capable)
Returns:
Remarks:
Please refer to the class DataLogging for more details on real-time data logging for the KUKA Light-Weight-Robot.
See also:
FastResearchInterface::StopLogging()

Definition at line 83 of file LoggingMethods.cpp.

int FastResearchInterface::StartRobot ( const unsigned int &  ControlMode,
const float &  TimeOutValueInSeconds = 120.0 
)

Starts the robot.

This method performs a complete start-up procedure of the robot arm. The following steps are executed:

  1. Before the KRL program FRIControl (cf.KRL File: FRIControl.src) is started by the user, the constructor FastResearchInterface::FastResearchInterface::() should be called in order to prevent any loss of UDP packages.
  2. If the KRC unit is not already in Monitor Mode (i.e., no communication between the remote host and the KRC unit is performed), the method waits for the call of the KRL function friOpen() to receive UDP messages in order to let the KRC unit switch to Monitor Mode.
  3. Once, the KRC unit runs in Monitor Mode, the method sets the KRL variable $FRI_FRM_INT[16] to a value of 10, which lets the KRL program FRIControl call the function friStart() in order to switch from Monitor Mode to Command Mode.
  4. In the transition phase, the following command variables are sent from the remote host to the KRC unit (see also: FastResearchInterface::SetControlScheme()):

    • Joint position control
      • Desired joint position vector = Current joint position vector

    • Cartesian impedance control
    • Joint impedance control
    • Joint torque control:
      • Desired joint torque vector = Zero vector

  5. After the KRC unit switched to Command Mode, the method waits until the robot is ready for operation, that is, until the result value of FastResearchInterface::IsMachineOK() is true.


The complete start-up procedure must not take longer than TimeOutValueInSeconds seconds. If completed successfully, the robot arm is ready for operation. This method should be used pairwise with the method FastResearchInterface::StopRobot() in order to ensure a safe and error-free operation.

Parameters:
ControlModeEither value of the enumeration FastResearchInterface::LWRControlModes:
If this method is called by an object derived from the class LWRBaseControllerInterface, this parameter is automatically set by their respective method for starting the robot.

TimeOutValueInSecondsTimeout value in seconds for the user to turn on the robot arm by using the KUKA Control Panel. The default value of this optional parameter is 120 seconds.
Returns:
  • ENOTCONN if no connection between the remote host and the KRC unit could be established. Please check
    • whether the KRC unit is turned on and the Ethernet cable (e.g., a crossed cable) is plugged in on both nodes,
    • whether the KRL program FRIControl (cf.KRL File: FRIControl.src) has been started, or
    • whether the KRC node is configured correctly in particular w.r.t. the network settings (cf. Introduction).
  • EALREADY if the KRC unit is already in command mode, that is, the KRL function friStart() was already called by a previous call of FastResearchInterface::StartRobot(). If the robot is not ready for operation (i.e., the result of FastResearchInterface::IsMachineOK() is false), call FastResearchInterface::StopRobot() first. It might be required to check whether the KRC unit is running correctly, and whether the KRL program KRL program FRIControl (cf.KRL File: FRIControl.src) is being executed.
  • ETIME if the start-up procedure could not be completed within the specified time interval of TimeOutValueInSeconds
  • EOK if no error occurred.
See also:
FastResearchInterface::StopRobot()

Definition at line 68 of file StartRobot.cpp.

Stops real-time data logging.

A call of this method resets the flag FastResearchInterface::LoggingIsActive, which stops the communication thread FastResearchInterface::KRCCommunicationThreadMain() from writing data into heap memory. After calling this method, FastResearchInterface::WriteLoggingDataFile() can be called, which finally writes all logged data into a file.

This method can only be called if FastResearchInterface::StartLogging() was called beforehand.

Within the class FastResearchInterface, the data logging methods are supposed to be used in the following order:

  1. FastResearchInterface::PrepareLogging() (not real-time capable)
  2. FastResearchInterface::StartLogging() (real-time capable)
  3. This method (real-time capable)
  4. FastResearchInterface::WriteLoggingDataFile() (not real-time capable)
Returns:
Attention:
The call of this method does not fulfill any real-time requirements.
Remarks:
Please refer to the class DataLogging for more details on real-time data logging for the KUKA Light-Weight-Robot.
See also:
FastResearchInterface::StartLogging()

Definition at line 105 of file LoggingMethods.cpp.

Stops the robot.

By calling this method, a complete shutdown procedure of the robot arm is performed. No matter whether the KRC unit runs in Monitor Mode or Command Mode, the KRL variable $FRI_FRM_INT[16] is set to a value of 20, which lets the KRL program FRIControl (cf.KRL File: FRIControl.src) call the function friStop() in order to switch to Monitor Mode. After the KRC unit switched to Monitor Mode, the method returns.

Returns:
  • ENOTCONN if no connection between the remote host and the KRC unit could be established. Please check
    • whether the KRC unit is turned on and the Ethernet cable (e.g., a crossed cable) is plugged in on both nodes,
    • whether the KRL program FRIControl (cf.KRL File: FRIControl.src) has been started, or
    • whether the KRC node is configured correctly in particular w.r.t. the network settings (cf. Introduction).
  • EOK if no error occurred.
See also:
FastResearchInterface::StartRobot()
Attention:

Definition at line 67 of file StopRobot.cpp.

static void * FastResearchInterface::TimerThreadMain ( void *  ThreadArgument) [static, protected]

Thread function for the timer thread.

Thread function for the KRC communication thread.

This function provides a basic timer functionality by periodically broadcasting a signal via a condition via a condition variable (FastResearchInterface::CondVarForTimer). This signal may be used by user applications calling FastResearchInterface::WaitForTimerTick().

Parameters:
ThreadArgumentA pointer the FastResearchInterface object of the calling thread.
Note:
This method is currently only implemented for the QNX Neutrino RTOS.
Todo:
Implement this method for other operating systems.
See also:
FastResearchInterface::WaitForTimerTick()

This function is the gateway to the KRC unit; it sends and receives data telegrams using the class friUDP. Right after the reception of one tFriMsrData package, a tFriCmdData is sent back to the KRC unit. Furthermore, a signal to all other threads is broadcasted through the condition variable FastResearchInterface::CondVarForDataReceptionFromKRC. Other threads may use the method FastResearchInterface::WaitForKRCTick() to wait for this signal.

Parameters:
ThreadArgumentA pointer the FastResearchInterface object of the calling thread.
See also:
FastResearchInterface::WaitForKRCTick()

Definition at line 154 of file TimerThreadMain.cpp.

int FastResearchInterface::WaitForKRCTick ( const unsigned int &  TimeoutValueInMicroSeconds = 0)

Blocks the calling thread until a message from the KRC unit has been received.

Parameters:
TimeoutValueInMicroSecondsNumber of microseconds used for the timeout functionality
Note:
The timeout functionality using the value of TimeoutValueInMicroSeconds is only implemented for QNX Neutrino RTOS.
Returns:
See also:
FastResearchInterface::WaitForTimerTick()

Definition at line 67 of file WaitForTicks.cpp.

int FastResearchInterface::WaitForTimerTick ( const unsigned int &  TimeoutValueInMicroSeconds = 0)

Blocks the calling thread until the timer thread sends a signal.

  • If set, this method resets the attribute FastResearchInterface::TimerFlag and returns (i.e., if a message has already been received, the method returns immediately).
  • If the attribute FastResearchInterface::TimerFlag is not set, this method blocks on the condition variable FastResearchInterface::CondVarForTimer. The corresponding signal for this condition variable will be generated by the thread FastResearchInterface::TimerThreadMain() immediately after its timer expired The timeout parameter TimeoutValueInMicroSeconds is only supported for the QNX Neutrino RTOS. If this value is set, the calling thread will be waked up after the expiration of this timeout value given in microseconds. If this value of TimeoutValueInMicroSeconds equals zero, no timeout functionality will be applied, and the calling thread blocks until a message from the KRC unit is received.
Parameters:
TimeoutValueInMicroSecondsNumber of microseconds used for the timeout functionality
Note:
The timeout functionality using the value of TimeoutValueInMicroSeconds is only implemented for QNX Neutrino RTOS.
Returns:
See also:
FastResearchInterface::WaitForKRCTick()

Definition at line 119 of file WaitForTicks.cpp.

Writes logged data to the output file and closes the file.

The data that has been sent and received between the calls of FastResearchInterface::StartLogging() and FastResearchInterface::StopLogging() is written into heap memory. This method writes this data into the file that was prepared by the method FastResearchInterface::PrepareLogging() and closes the file.

This method can only be called if FastResearchInterface::PrepareLogging() was called beforehand.

Within the class FastResearchInterface, the data logging methods are supposed to be used in the following order:

  1. FastResearchInterface::PrepareLogging() (not real-time capable)
  2. FastResearchInterface::StartLogging() (real-time capable)
  3. FastResearchInterface::StopLogging() (real-time capable)
  4. This method (not real-time capable)
Returns:
Attention:
The call of this method does not fulfill any real-time requirements.
Remarks:
Please refer to the class DataLogging for more details on real-time data logging for the KUKA Light-Weight-Robot.
See also:
DataLogging::WriteToFile()

Definition at line 127 of file LoggingMethods.cpp.


Member Data Documentation

tFriCmdData FastResearchInterface::CommandData [protected]

Data structure object containing a copy of a complete data telegram to be sent to the KRC unit.

Definition at line 1941 of file FastResearchInterface.h.

Condition variable used by the KRC communication thread FastResearchInterface::KRCCommunicationThreadMain() for broadcasting after the reception of a message from the KRC unit.

Definition at line 1866 of file FastResearchInterface.h.

Condition variable used during the creation of new threads.

See also:
ThreadCreated
MutexForThreadCreation

Definition at line 1878 of file FastResearchInterface.h.

pthread_cond_t FastResearchInterface::CondVarForTimer [protected]

Condition variable used by the timer thread FastResearchInterface::TimerThreadMain() for broadcasting after the firing of its timer.

Definition at line 1856 of file FastResearchInterface.h.

Contains the current control scheme.

See also:
FastResearchInterface::LWRControlModes

Definition at line 1740 of file FastResearchInterface.h.

Contains the cycle time in seconds (specified in the initialization file)

See also:
sec_InitFile

Definition at line 1807 of file FastResearchInterface.h.

Pointer to a DataLogging object used for real-time logging of low-level control data.

Definition at line 1923 of file FastResearchInterface.h.

POSIX thread identifier for the KRC communication thread FastResearchInterface::KRCCommunicationThreadMain()

Definition at line 1887 of file FastResearchInterface.h.

A pointer to an array of char values containing the name of the log file (specified in the initialization file)

See also:
sec_InitFile

Definition at line 1718 of file FastResearchInterface.h.

A pointer to an array of char values containing the path of the log file (specified in the initialization file)

See also:
sec_InitFile

Definition at line 1707 of file FastResearchInterface.h.

Stores which logging methods has been called lately.

Definition at line 1685 of file FastResearchInterface.h.

pthread_t FastResearchInterface::MainThread [protected]

POSIX thread identifier for the thread calling the constructor FastResearchInterface::FastResearchInterface()

Definition at line 1905 of file FastResearchInterface.h.

Mutex to protect FastResearchInterface::TimerFlag.

Definition at line 1825 of file FastResearchInterface.h.

pthread_mutex_t FastResearchInterface::MutexForControlData [protected]
pthread_mutex_t FastResearchInterface::MutexForLogging [protected]

Mutex to protect FastResearchInterface::LoggingIsActive.

Definition at line 1834 of file FastResearchInterface.h.

pthread_mutex_t FastResearchInterface::MutexForThreadCreation [protected]

Mutex used during the creation of new threads.

See also:
ThreadCreated
CondVarForThreadCreation

Definition at line 1846 of file FastResearchInterface.h.

Used as indication for the KRC communication thread to terminate itself.

Definition at line 1654 of file FastResearchInterface.h.

Contains the maximum number of logging file entries (specified in the initialization file)

See also:
sec_InitFile

Definition at line 1750 of file FastResearchInterface.h.

Pointer to a Console object used for message output through a low-priority thread.

Definition at line 1914 of file FastResearchInterface.h.

Contains the priority of the KRC communication thread (specified in the initialization file)

See also:
FastResearchInterface::KRCCommunicationThreadMain()
sec_InitFile

Definition at line 1762 of file FastResearchInterface.h.

Contains the priority of the thread that called the constructor (specified in the initialization file)

See also:
sec_InitFile

Definition at line 1784 of file FastResearchInterface.h.

Contains the priority of the output thread (specified in the initialization file)

See also:
Console::Console()
sec_InitFile

Definition at line 1796 of file FastResearchInterface.h.

Contains the priority of the timer thread (specified in the initialization file)

See also:
FastResearchInterface::TimerThreadMain()
sec_InitFile

Definition at line 1774 of file FastResearchInterface.h.

tFriMsrData FastResearchInterface::ReadData [protected]

Data structure object containing a copy of a complete received data telegram from the KRC unit.

Definition at line 1932 of file FastResearchInterface.h.

A pointer to an array of char values containing the name of the robot (specified in the initialization file)

See also:
sec_InitFile

Definition at line 1696 of file FastResearchInterface.h.

A pointer to an array of char values containing the description of the complete robot state.

See also:
FastResearchInterface::GetCompleteRobotStateAndInformation()

Definition at line 1729 of file FastResearchInterface.h.

Flag to terminate the communication thread.

Definition at line 1645 of file FastResearchInterface.h.

Used as indication for the timer thread to terminate itself.

Definition at line 1627 of file FastResearchInterface.h.

Used during the creation of new threads to acknowledge the creating thread that the new thread is running.

See also:
MutexForThreadCreation
CondVarForThreadCreation

Definition at line 1676 of file FastResearchInterface.h.

Set by the timer thread each time its timer fires.

Definition at line 1636 of file FastResearchInterface.h.

pthread_t FastResearchInterface::TimerThread [protected]

POSIX thread identifier for the timer thread FastResearchInterface::TimerThreadMain()

Definition at line 1896 of file FastResearchInterface.h.


The documentation for this class was generated from the following files:
This document was generated with Doxygen on Thu Apr 12 2012 11:18:55. User documentation of the Fast Research Interface Library for the KUKA Lightweight Robot IV by the Stanford Robotics Research Group. Copyright 2010–2012.