Fast Research Interface Library  Manual and Documentation
Public Member Functions
LWRJointTorqueController Class Reference

Joint torque controller interface for the KUKA Light-Weight Robot IV. More...

#include <LWRJointTorqueController.h>

Inheritance diagram for LWRJointTorqueController:
LWRBaseControllerInterface

List of all members.

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.

Detailed Description

Joint torque controller interface for the KUKA Light-Weight Robot IV.

Definition at line 55 of file LWRJointTorqueController.h.


Constructor & Destructor Documentation

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

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 70 of file LWRJointTorqueController.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 83 of file LWRJointTorqueController.h.


Member Function Documentation

void LWRJointTorqueController::SetCommandedJointTorques ( const float *  CommandedJointTorques) [inline]

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

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

Implements LWRBaseControllerInterface.

Definition at line 97 of file LWRJointTorqueController.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.