absoluteMotion.cpp

Performs point to point trapezoidal profile motion.

/* absoluteMotion.cpp

 Copyright(c) 1998-2009 by Robotic Systems Integration, Inc. All rights reserved.
 This software contains proprietary and confidential information of Robotic 
 Systems Integration, Inc. (RSI) and its suppliers. Except as may be set forth 
 in the license agreement under which this software is supplied, disclosure, 
 reproduction, or use with controls other than those provided by RSI or suppliers
 for RSI is strictly prohibited without the prior express written consent of 
 Robotic Systems Integration.
 
 This sample code presumes that the user has set the tuning paramters(PID, PIV, etc.) 
 prior to running this program so that the motor can rotate in a stable manner.

 This sample application moves a single axis in trapezoidal profile to an absolute 
 distance set by RELATIVE_POSITION below. For a simple trapezoidal motion profile using
 'Relative move' please see motion1_relative.cpp
 
 There is a minimal error checking in this sample.

 For any questions regarding this sample code please visit our documentation at www.roboticsys.com


 Warning!  This is a sample program to assist in the integration of your motion 
 controller with your application.  It may not contain all of the logic and safety
 features that your application requires.
*/


#include "rsi.h"

using namespace RSI::RapidCode::SynqNet;

#define AXIS_NUMBER             0
#define RELATIVE_POSITION         20000
#define VELOCITY              5000
#define ACCELERATION            10000
#define DECELERATION              20000


void absoluteMotionMain()
{
  try
  {
    MotionController    *controller ;
    Axis        *axis ;

    // initialize MotionController class
    controller = MotionController::CreateFromBoard(0);  

    // initialize Axis class  
    axis = controller->AxisGet( AXIS_NUMBER);

    axis->ClearFaults();
    axis->AmpEnableSet(true);

    printf("Absolute Move\n\n");
    printf("Trapezoidal Profile: In Motion...\r");
    //Command simple trapezoidal motion
    axis->MoveTrapezoidal(RELATIVE_POSITION, VELOCITY, ACCELERATION, DECELERATION);

    axis->MotionDoneWait();

    printf("Trapezoidal Profile: Completed\n\n");
    
  }
  catch (RsiError *err)
  {
    printf("%s\n", err->text);
  }
}