|
Fast Research Interface Library
Manual and Documentation
|
Base class for other controller interface classes of the KUKA Fast Research Interface for the Light-Weight Robot IV. More...
#include <LWRBaseControllerInterface.h>
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 | |
| FastResearchInterface * | FRI |
| A pointer to the actual object of the class FastResearchInterface. | |
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.
Definition at line 95 of file LWRBaseControllerInterface.h.
| 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
InitFileName using the method FastResearchInterface::ReadInitFile(), which further on uses an object of the class InitializationFileEntry, In case,
InitFileName cannot be opened, InitFileName does not contain all required parameters (cf. The Initialization File for the Fast Research Interface Library), or the constructor lets the calling process terminate and exits with a value of EXIT_FAILURE.
| InitFileName | A 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. |
SCHED_FIFO).Definition at line 113 of file LWRBaseControllerInterface.h.
| LWRBaseControllerInterface::~LWRBaseControllerInterface | ( | void | ) | [inline] |
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:
SIGTERM) will be sent to the thread FastResearchInterface::KRCCommunicationThread. Definition at line 130 of file LWRBaseControllerInterface.h.
| const char * LWRBaseControllerInterface::GetCompleteRobotStateAndInformation | ( | void | ) | [inline] |
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.
char values describing the complete state of the robotDefinition 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)
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.
| MeasuredJointPositions | A 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. |
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.
| MeasuredJointTorques | A 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. |
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:
true if the machine is ready for operationfalse otherwiseDefinition 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:
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.
| FileIdentifier | A pointer to an array of char values containing a string to identify the written log file. This parameter is optional. |
EINVAL if a former logging file has not been closed (i.e., if FastResearchInterface::PrepareLogging() was called without a succeeding call of FastResearchInterface::WriteLoggingDataFile(). EBADF if the file could not be created. EOK if no error occurred. 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.
| Format | Formats 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. |
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.
| int LWRBaseControllerInterface::StartLogging | ( | void | ) | [inline] |
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:
EINVAL if the method FastResearchInterface::PrepareLogging() has not been called beforehand. EOK otherwise. 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:
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. friOpen() to receive UDP messages in order to let the KRC unit switch to Monitor Mode. $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. 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.
| ControlMode | Either value of the enumeration FastResearchInterface::LWRControlModes:
|
| TimeOutValueInSeconds | Timeout 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. |
ENOTCONN if no connection between the remote host and the KRC unit could be established. Please check FRIControl (cf.KRL File: FRIControl.src) has been started, or 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. 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:
EINVAL if the method FastResearchInterface::StartLogging() has not been called beforehand. EOK otherwise. 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.
ENOTCONN if no connection between the remote host and the KRC unit could be established. Please check FRIControl (cf.KRL File: FRIControl.src) has been started, or EOK if no error occurred. friStop(), the robot arm power may be still turned on. In the cases of
this may lead to an uncontrolled and/or undesired behavior of the robot arm. 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.
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 (or until FastResearchInterface::~FastResearchInterface() sends a termination signal). | TimeoutValueInMicroSeconds | Number of microseconds used for the timeout functionality |
TimeoutValueInMicroSeconds is only implemented for QNX Neutrino RTOS.EOK if a KRC message has been correctly received. EAGAIN if there are insufficient system resources are available. ETIMEDOUT if the specified timeout expired. EINVAL if an internal error occurred (cf. http://www.qnx.com/developers/docs/6.3.2/neutrino/lib_ref/p/pthread_cond_wait.html or http://www.qnx.com/developers/docs/6.3.2/neutrino/lib_ref/p/pthread_cond_timedwait.html, respectively). 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.
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. | TimeoutValueInMicroSeconds | Number of microseconds used for the timeout functionality |
TimeoutValueInMicroSeconds is only implemented for QNX Neutrino RTOS.EOK if a KRC message has been correctly received. EAGAIN if there are insufficient system resources are available. ETIMEDOUT if the specified timeout expired. EINVAL if an internal error occurred (cf. http://www.qnx.com/developers/docs/6.3.2/neutrino/lib_ref/p/pthread_cond_wait.html or http://www.qnx.com/developers/docs/6.3.2/neutrino/lib_ref/p/pthread_cond_timedwait.html, respectively). Definition at line 246 of file LWRBaseControllerInterface.h.
| int LWRBaseControllerInterface::WriteLoggingDataFile | ( | void | ) | [inline] |
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:
EINVAL if the method FastResearchInterface::PrepareLogging() has not been called beforehand. EOF if the file could not be closed. EOK otherwise. Definition at line 372 of file LWRBaseControllerInterface.h.
FastResearchInterface * LWRBaseControllerInterface::FRI [protected] |
A pointer to the actual object of the class FastResearchInterface.
Definition at line 387 of file LWRBaseControllerInterface.h.