Reflexxes Motion Libraries Manual and Documentation (Type II, Version 1.2.2)

Position-based Example 1

Below, you can find the source code of a very first sample application that makes use of the position-based Reflexxes algorithm. The source file can be found in the folder

/src/RMLPositionSampleApplications/RMLPositionSampleApplication1.cpp

The resulting trajectory of this sample program is displayed below the source code.



//  ---------------------- Doxygen info ----------------------
//  ----------------------------------------------------------
//   For a convenient reading of this file's source code,
//   please use a tab width of four characters.
//  ----------------------------------------------------------


#include <stdio.h>
#include <stdlib.h>

#include <ReflexxesAPI.h>
#include <RMLPositionFlags.h>
#include <RMLPositionInputParameters.h>
#include <RMLPositionOutputParameters.h>


//*************************************************************************
// defines

#define CYCLE_TIME_IN_SECONDS                   0.001
#define NUMBER_OF_DOFS                          3


//*************************************************************************
// Main function to run the process that contains the test application
// 
// This function contains source code to get started with the  
// Reflexxes Motion Library. Only a minimum amount of functionality is
// contained in this program: a simple trajectory for a
// three-degree-of-freedom system is executed. This code snippet
// directly corresponds to the example trajectories shown in the 
// documentation.
//*************************************************************************
int main()
{
    // ********************************************************************
    // Variable declarations and definitions
    
    int                         ResultValue                 =   0       ;

    ReflexxesAPI                *RML                        =   NULL    ;
    
    RMLPositionInputParameters  *IP                         =   NULL    ;
    
    RMLPositionOutputParameters *OP                         =   NULL    ;
    
    RMLPositionFlags            Flags                                   ;

    // ********************************************************************
    // Creating all relevant objects of the Reflexxes Motion Library    
    
    RML =   new ReflexxesAPI(                   NUMBER_OF_DOFS
                                            ,   CYCLE_TIME_IN_SECONDS   );
    
    IP  =   new RMLPositionInputParameters(     NUMBER_OF_DOFS          );
    
    OP  =   new RMLPositionOutputParameters(    NUMBER_OF_DOFS          );
    
    // ********************************************************************
    // Set-up a timer with a period of one millisecond
    // (not implemented in this example in order to keep it simple)
    // ********************************************************************
    
    printf("-------------------------------------------------------\n"  );
    printf("Reflexxes Motion Libraries                             \n"  );
    printf("Example: RMLPositionSampleApplication1                 \n\n");
    printf("This example demonstrates the most basic use of the    \n"  );
    printf("Reflexxes Motion Library (RML, class ReflexxesAPI)     \n"  );
    printf("using position-based On-Line Trajectory Generation.    \n\n");
    printf("Copyright (C) 2012 Reflexxes GmbH                      \n"  );
    printf("-------------------------------------------------------\n"  );

    // ********************************************************************
    // Set-up the input parameters
    
    // In this test program, arbitrary values are chosen. If executed on a
    // real robot or mechanical system, the position is read and stored in
    // an RMLPositionInputParameters::CurrentPositionVector vector object.
    // For the very first motion after starting the controller, velocities
    // and acceleration are commonly set to zero. The desired target state
    // of motion and the motion constraints depend on the robot and the
    // current task/application.
    // The internal data structures make use of native C data types
    // (e.g., IP->CurrentPositionVector->VecData is a pointer to
    // an array of NUMBER_OF_DOFS double values), such that the Reflexxes
    // Library can be used in a universal way.
    
    // IMPORTANT REMARK: Please note that the values of MaxJerk and
    // CurrentAcceleration are only applied by the Type IV Reflexxes
    // Motion Library.
    
    IP->CurrentPositionVector->VecData      [0] =    100.0      ;
    IP->CurrentPositionVector->VecData      [1] =      0.0      ;
    IP->CurrentPositionVector->VecData      [2] =     50.0      ;
    
    IP->CurrentVelocityVector->VecData      [0] =    100.0      ;
    IP->CurrentVelocityVector->VecData      [1] =   -220.0      ;
    IP->CurrentVelocityVector->VecData      [2] =    -50.0      ;
    
    IP->CurrentAccelerationVector->VecData  [0] =   -150.0      ;
    IP->CurrentAccelerationVector->VecData  [1] =    250.0      ;
    IP->CurrentAccelerationVector->VecData  [2] =    -50.0      ;   

    IP->MaxVelocityVector->VecData          [0] =    300.0      ;
    IP->MaxVelocityVector->VecData          [1] =    100.0      ;
    IP->MaxVelocityVector->VecData          [2] =    300.0      ;
    
    IP->MaxAccelerationVector->VecData      [0] =    300.0      ;
    IP->MaxAccelerationVector->VecData      [1] =    200.0      ;
    IP->MaxAccelerationVector->VecData      [2] =    100.0      ;       

    IP->MaxJerkVector->VecData              [0] =    400.0      ;
    IP->MaxJerkVector->VecData              [1] =    300.0      ;
    IP->MaxJerkVector->VecData              [2] =    200.0      ;
    
    IP->TargetPositionVector->VecData       [0] =   -600.0      ;
    IP->TargetPositionVector->VecData       [1] =   -200.0      ;
    IP->TargetPositionVector->VecData       [2] =   -350.0      ;
    
    IP->TargetVelocityVector->VecData       [0] =    50.0       ;
    IP->TargetVelocityVector->VecData       [1] =   -50.0       ;
    IP->TargetVelocityVector->VecData       [2] =  -200.0       ;

    IP->SelectionVector->VecData            [0] =   true        ;
    IP->SelectionVector->VecData            [1] =   true        ;
    IP->SelectionVector->VecData            [2] =   true        ;

    // ********************************************************************
    // Starting the control loop
    
    while (ResultValue != ReflexxesAPI::RML_FINAL_STATE_REACHED)
    {
    
        // ****************************************************************                                 
        // Wait for the next timer tick
        // (not implemented in this example in order to keep it simple)
        // **************************************************************** 
    
        // Calling the Reflexxes OTG algorithm
        ResultValue =   RML->RMLPosition(       *IP
                                            ,   OP
                                            ,   Flags       );
                                            
        if (ResultValue < 0)
        {
            printf("An error occurred (%d).\n", ResultValue );
            break;
        }
        
        // ****************************************************************                                 
        // Here, the new state of motion, that is
        //
        // - OP->NewPositionVector      
        // - OP->NewVelocityVector      
        // - OP->NewAccelerationVector
        //
        // can be used as input values for lower level controllers. In the 
        // most simple case, a position controller in actuator space is 
        // used, but the computed state can be applied to many other 
        // controllers (e.g., Cartesian impedance controllers, 
        // operational space controllers).
        // ****************************************************************

        // ****************************************************************
        // Feed the output values of the current control cycle back to 
        // input values of the next control cycle
        
        *IP->CurrentPositionVector      =   *OP->NewPositionVector      ;
        *IP->CurrentVelocityVector      =   *OP->NewVelocityVector      ;
        *IP->CurrentAccelerationVector  =   *OP->NewAccelerationVector  ;
    }

    // ********************************************************************
    // Deleting the objects of the Reflexxes Motion Library end terminating
    // the process
    
    delete  RML         ;
    delete  IP          ;
    delete  OP          ;

    exit(EXIT_SUCCESS)  ;
}



PositionExample1.png

Resulting trajectory of example 1 for position-based trajectory generation (RMLPositionSampleApplication1.cpp).


Note:
The variables

are only used by the Type IV Reflexxes Motion Library.



See also:
Description of Output Values
Position-based Example 2
Velocity-based Example 4
User documentation of the Reflexxes Motion Libraries by Reflexxes GmbH (Company Information, Impressum). This document was generated with Doxygen on Mon May 14 2012 22:55:39. Copyright 2010–2012.