Fast Research Interface Library  Manual and Documentation
Public Member Functions | Protected Attributes
LWRBaseControllerInterface Class Reference

Base class for other controller interface classes of the KUKA Fast Research Interface for the Light-Weight Robot IV. More...

#include <LWRBaseControllerInterface.h>

Inheritance diagram for LWRBaseControllerInterface:
LWRCartImpedanceController LWRJointImpedanceController LWRJointPositionController LWRJointTorqueController

List of all members.

Public Member Functions

 LWRBaseControllerInterface (const char *InitFileName)
 Constructor.
 ~LWRBaseControllerInterface (void)
 Destructor.
virtual int StartRobot (const float &TimeOutValueInSeconds)=0
 Starts the robot.
int StopRobot (void)
 Stops the robot.
int GetMeasuredJointPositions (float *MeasuredJointPositions)
 Reads the measured joint position vector from the latest data telegram of the KRC unit.
int GetMeasuredJointTorques (float *MeasuredJointTorques)
 Reads the measured joint torque vector from the latest data telegram of the KRC unit.
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.
float GetCycleTime (void)
 Returns the communication cycle time between the KRC unit and the remote host (read from the latest data telegram of the KRC unit)
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 Attributes

FastResearchInterfaceFRI
 A pointer to the actual object of the class FastResearchInterface.

Detailed Description

Base class for other controller interface classes of the KUKA Fast Research Interface for the Light-Weight Robot IV.

This class constitutes the base class for the three different controller interface classes, which represent the actual user API for the Fast Research Library:

This base class only features one attribute, which is a pointer to an object of the class FastResearchInterface. Most of the functionality of the class FastResearchInterface remains hidden, and only a small subset that is actually necessary for convenient user API is used in this base class and it derivatives.

See also:
FastResearchInterface
LWRJointPositionController
LWRCartImpedanceController
LWRJointImpedanceController

Definition at line 95 of file LWRBaseControllerInterface.h.


Constructor & Destructor Documentation

LWRBaseControllerInterface::LWRBaseControllerInterface ( const char *  InitFileName) [inline]

Constructor.

The constructor creates the actual object of the class FastResearchInterface, which is used by this class.

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 113 of file LWRBaseControllerInterface.h.

Destructor.

The destructor deletes the actual object of the class FastResearchInterface, which is used by this class.

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 130 of file LWRBaseControllerInterface.h.


Member Function Documentation

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 291 of file LWRBaseControllerInterface.h.

float LWRBaseControllerInterface::GetCycleTime ( void  ) [inline]

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 276 of file LWRBaseControllerInterface.h.

int LWRBaseControllerInterface::GetMeasuredJointPositions ( float *  MeasuredJointPositions) [inline]

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

Returns:
  • ENOTCONN if no connection between the remote host and the KRC unit exists.
  • EOK if no error occurred.

Definition at line 177 of file LWRBaseControllerInterface.h.

int LWRBaseControllerInterface::GetMeasuredJointTorques ( float *  MeasuredJointTorques) [inline]

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

Returns:
  • ENOTCONN if no connection between the remote host and the KRC unit exists.
  • EOK if no error occurred.

Definition at line 207 of file LWRBaseControllerInterface.h.

bool LWRBaseControllerInterface::IsMachineOK ( void  ) [inline]

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 261 of file LWRBaseControllerInterface.h.

int LWRBaseControllerInterface::PrepareLogging ( const char *  FileIdentifier = NULL) [inline]

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 327 of file LWRBaseControllerInterface.h.

int LWRBaseControllerInterface::printf ( const char *  Format,
  ... 
) [inline]

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 305 of file LWRBaseControllerInterface.h.

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 342 of file LWRBaseControllerInterface.h.

int LWRBaseControllerInterface::StartRobot ( const float &  TimeOutValueInSeconds) [inline, pure virtual]

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

Implemented in LWRCartImpedanceController, LWRJointImpedanceController, LWRJointPositionController, and LWRJointTorqueController.

int LWRBaseControllerInterface::StopLogging ( void  ) [inline]

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 357 of file LWRBaseControllerInterface.h.

int LWRBaseControllerInterface::StopRobot ( void  ) [inline]

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 156 of file LWRBaseControllerInterface.h.

int LWRBaseControllerInterface::WaitForKRCTick ( const unsigned int &  TimeoutValueInMicroSeconds = 0) [inline]

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 231 of file LWRBaseControllerInterface.h.

int LWRBaseControllerInterface::WaitForTimerTick ( const unsigned int &  TimeoutValueInMicroSeconds = 0) [inline]

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 246 of file LWRBaseControllerInterface.h.

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 372 of file LWRBaseControllerInterface.h.


Member Data Documentation

A pointer to the actual object of the class FastResearchInterface.

Definition at line 387 of file LWRBaseControllerInterface.h.


The documentation for this class was generated from the following file:
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.