|
Fast Research Interface Library
Manual and Documentation
|
Joint torque controller interface for the KUKA Light-Weight Robot IV. More...
#include <LWRJointTorqueController.h>
Public Member Functions | |
| LWRJointTorqueController (const char *InitFileName) | |
| Constructor. | |
| ~LWRJointTorqueController (void) | |
| Destructor. | |
| int | StartRobot (const float &TimeOutValueInSeconds=120.0) |
| Starts the robot. | |
| void | SetCommandedJointTorques (const float *CommandedJointTorques) |
| Copies the desired joint torque vector into the data telegram to be send to the KRC unit. | |
Joint torque controller interface for the KUKA Light-Weight Robot IV.
Definition at line 55 of file LWRJointTorqueController.h.
| LWRJointTorqueController::LWRJointTorqueController | ( | 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 70 of file LWRJointTorqueController.h.
| LWRJointTorqueController::~LWRJointTorqueController | ( | 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 83 of file LWRJointTorqueController.h.
| void LWRJointTorqueController::SetCommandedJointTorques | ( | const float * | CommandedJointTorques | ) | [inline] |
Copies the desired joint torque vector into the data telegram to be send to the KRC unit.
| CommandedJointTorques | A 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. |
Definition at line 116 of file LWRJointTorqueController.h.
| int LWRJointTorqueController::StartRobot | ( | const float & | TimeOutValueInSeconds = 120.0 | ) | [inline, 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. Implements LWRBaseControllerInterface.
Definition at line 97 of file LWRJointTorqueController.h.