schall.c -- Single-Axis Sinusoidal Commutation Sample Program with Hall Initialization
/* ScHall.C */

/* Copyright(c) 1991-2002 by Motion Engineering, Inc.  All rights reserved.
 *
 * This software contains proprietary and confidential information of
 * Motion Engineering Inc., and its suppliers.  Except as may be set forth
 * in the license agreement under which  this software is supplied, use,
 * disclosure, or  reproduction is prohibited without the prior express
 * written consent of Motion Engineering, Inc.
 */

/*

:Single-Axis Sinusoidal Commutation Sample Program with Hall Initialization

This program reads the Hall - I/O bit state, then sets the commutation
 table entry point to match the active Hall sensor.  This version latches
 position and up-dates the commutation entry point based on the first
 Hall transition (latches upon a single I/O with a specific edge).




        Axis 0:     Uses Hall-type initialization with a small trapezoidal
                    move (closed-loop) to the first Hall transition. Updates
                    commutation position based on the Hall transition location.

    Background:     The initial state of the three Hall sensors provides six
                    possible magnetic sectors of 60 degrees which may contain
                    the motor field vector (i.e., rotor magnetic position).
                    This program uses the following logic table:


 Mag.Phase Angle:    0 - 60 60 - 120 120 - 180  180 - 240 240 - 300  300 - 360
                    -----------------------------------------------------------
                    |       |       |         |          |          |         |
    Hall A Sensor   |  On   |   On  |   On    |    Off   |   Off    |    Off  |
                    |       |       |         |          |          |         |
    Hall B Sensor   |  Off  |   Off |   On    |    On    |   On     |    Off  |
                    |       |       |         |          |          |         |
    Hall C Sensor   |  On   |   Off |   Off   |    Off   |   On     |    On   |
                    -----------------------------------------------------------

 Hall Logic (C,B,A) (101)     (001)    (011)      (010)     (110)      (100)

 Hall Region            5       1        3          2         6          4


            The rotor magnetic field vector will initially be located within
            one of these six regions.  Sufficient accuracy for closed-loop control
            is obtained by assigning the magnetic location to the mid-point of
            the active region.  Thus, the actual commutation accuracy will be +/- 30
            electrical degrees (assuming the halls have been accurately located on your
            motor).  The motor is configured under closed-loop control and a slow
            trapezoidal move is implemented to the first observed Hall transition.
            The commutation position is then corrected to reflect the exact magnetic
            position of the Hall transition point.

            Note -  The XMP calculates: A Phase DAC Output = sin(Theta + 120)
                                        B Phase DAC Output = sin(Theta)

            Note -  See the XMP Installation Manual for information on wiring the
                    Transceiver I/O to the Hall sensors.

            Note -  #defs are provided to reverse encoder and DAC phasing.  Be aware
                    that the DAC phasing change should be called only once.



 Configure the XMP:

            Axis 0  Filter 0   Motor 0


 Configure Transceivers as input (default state):

            This sample application configures three transceivers on one motor.


Warning!   This program disables the HW Limits, Amp Fault, Home and Error Limit.

Warning!  The commutation configuration parameters will be different
 for your application.  Take particular care in setting the open-loop
 continuous DAC OutputLevel as this must be a safe level for your specific
 drive and motor combination.  Please read the MEI Sinusoidal Commutation
 Documentation.

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

*/

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

#include "stdmpi.h"
#include "stdmei.h"

#include "apputil.h"

#if defined(ARG_MAIN_RENAME)
#define main ScHall

argMainRENAME(main, ScHall)
#endif

#define AXIS_CNT    (1)
#define SLOW        (5.E2)      /* velocity to first Hall transition, cts/sec */
#define SLOW_ACCEL  (1.E4)      /* acceleration to first Hall transition cts/sec */
#define FAST        (5.E4)      /* velocity to shift commutation pointer, cts/sec */
#define FAST_ACCEL  (5.E5)      /* acceleration to shift comm. pointer cts/sec */

#undef USERIO

#if defined USERIO    /* Toggle the user bit associated with the motor */
#define BIT_MASK MEIXmpMotorIOMaskUSER   /* user IO Bit Mask */
#define BIT_IO   MEIXmpMotorIOBitUSER   /* user IO Bit */
#endif


/* User Settings MotorIO transceivers */
#define IO_CONFIG_IN        (MEIMotorTransceiverConfigINPUT) /* INPUT or OUTPUT   */
#define TRANSC_A_ID         (MEIMotorTransceiverIdA)
#define TRANSC_A_MASK       (MEIMotorTransceiverMaskA)
#define TRANSC_B_ID         (MEIMotorTransceiverIdB)
#define TRANSC_B_MASK       (MEIMotorTransceiverMaskB)
#define TRANSC_C_ID         (MEIMotorTransceiverIdC)
#define TRANSC_C_MASK       (MEIMotorTransceiverMaskC)


/* Command line arguments and defaults */
long    axisNumber      = 0;
long    motionNumber    = 0;
long    motorNumber     = 0;


/* Capture Parameters */
#define ACTIVE_LOW_EDGE     (0)
#define ACTIVE_HIGH_EDGE    (1)

long captureActiveEdge = ACTIVE_HIGH_EDGE;      /* capture on high edge */

Arg argList[] = {
    {   "-axis",    ArgTypeLONG,    &axisNumber,    },
    {   "-motion",  ArgTypeLONG,    &motionNumber,  },

    {   NULL,       ArgTypeINVALID, NULL,   }
};

/* Option to reverse encoder phasing */
#undef ReverseEncPhasing
/* Option to reverse DAC phasing */
#undef ReverseDACPhasing
#undef DumpCommParameters


void SetPositionZero(MPIAxis axis);


int
    main(int    argc,
         char   *argv[])
{
    MPIControl  control;    /* motion controller handle */
    MPIAxis     axis;       /* axis handles */
    MPIFilter   filter;     /* filter handles */
    MPIMotor    motor;      /* motor handles  */
    MPICapture  capture;    /* capture handles */


    MPIControlConfig    controlConfig;  /* motion controller configuration */
    MPIAxisConfig       axisConfig;     /* axis configuration */
    MPIFilterGain       gain;
    MPIMotorConfig      motorConfig;    /* motor configuration */
    MPIMotorEventConfig eventConfig;
    MPIMotorIo          io;
    MPICaptureConfig    captureConfig;  /* capture configuration */
    MPICaptureStatus    captureStatus;  /* capture status */


    MEIMotorConfig      motorConfigXmp; /* contains transceiver configuration */
    MEIFilterGainPID    *pid;
    MEIXmpCommutationBlock  *commutation;

    MPIMotion       motion; /* Coordinated motion object handles */
    MPIMotionParams params; /* Motion parameters */
    MPITrajectory   trajectory;

    MPIControlType          controlType;
    MPIControlAddress       controlAddress;

    long    returnValue;    /* return value from library */
    long    iTranState;     /* value of the Hall transceiver word */
    long    iOffset;        /* integer value to move comm. Offset parameter */
    long    nEncCountPerCycle =  4096;          /* number of encoder counts per motor revolution */
    float   OpenDAC_Level     = (float)3277.0;  /* Open Loop DAC Level where 32767. = 10V) */
    float   N_CYCLES          = (float)3.0;     /* number of elec. cycles per motor rev. */

#if defined(ReverseDACPhasing)
    long    dacCount;
    long    dacNumber[MPIMotorDacCountMAX];
    long    number;
#endif

    double          command;
    double          endposition;
    double          LminusTh;
    double          origin;
    double          origLatchPosition, latchedPosition, latchPosChange;

    float   inPositionLimit = (float)1.0e10;

    long    argIndex;
    long    captureNumber;


    /* Parse command line for Control type and address */

    argIndex =
        argControl(argc,
                   argv,
                   &controlType,
                   &controlAddress);

    /* Parse command line for application-specific arguments */

    while (argIndex < argc) {
        long    argIndexNew;

        argIndexNew = argSet(argList, argIndex, argc, argv);

        if (argIndexNew <= argIndex) {
            argIndex = argIndexNew;
            break;
        }
        else {
            argIndex = argIndexNew;
        }
    }

    /* Check for unknown/invalid command line arguments */

    if ((argIndex < argc) ||
        (axisNumber   >= MEIXmpMAX_Axes) ||
        (motionNumber >= MEIXmpMAX_MSs)) {
        meiPlatformConsole("usage: %s %s\n"
                           "\t\t[-axis # (0 .. %d)]\n"
                           "\t\t[-motion # (0 .. %d)]\n",
                            argv[0],
                            ArgUSAGE,
                            MEIXmpMAX_Axes - 1,
                            MEIXmpMAX_MSs - 1);
        exit(MPIMessageARG_INVALID);
    }


    /* Calculate default capture number for axisNumber */
    captureNumber = (axisNumber/MEIXmpMotorsPerBlock) * MEIXmpMaxLatches +
                    (axisNumber % MEIXmpMotorsPerBlock) * 2;

    /* Create device driver motion controller object  */

    control =
        mpiControlCreate(controlType,
                         &controlAddress);
    msgCHECK(mpiControlValidate(control));

    /*  Initialize motion controller  */
    returnValue = mpiControlInit(control);
    msgCHECK(returnValue);

    /*
       Configure motion controller
       Set Sample Rate = 2 kHz (this is the default)
       Configure for commutation B phase DACs
       Configure ADCs
     */
    returnValue =
        mpiControlConfigGet(control,
                            &controlConfig,
                            NULL);
    msgCHECK(returnValue);

    controlConfig.sampleRate = 2000;

    /*
        When supporting commutation,
        Cmd and Aux DACs must be enabled.
        Enabling the same number of Cmd and Aux DACs as there are motors.
     */
    controlConfig.cmdDacCount = controlConfig.motorCount;
    controlConfig.auxDacCount = controlConfig.motorCount;

    /* Configure required number of A/D  */
    controlConfig.adcCount = 8;

    returnValue =
        mpiControlConfigSet(control,
                            &controlConfig,
                            NULL);
    msgCHECK(returnValue);

    /* Create axis, filter and motor controller objects */

    axis =
        mpiAxisCreate(control,
                      axisNumber);
    msgCHECK(mpiAxisValidate(axis));

    filter =
        mpiFilterCreate(control,
                      axisNumber);
    msgCHECK(mpiFilterValidate(filter));

    motor =
        mpiMotorCreate(control,
                      motorNumber);
    msgCHECK(mpiMotorValidate(motor));

    /* Create capture object for captureNumber */
    capture =
        mpiCaptureCreate(control,
                         captureNumber);
    msgCHECK(mpiCaptureValidate(capture));


    /* Disable the amplifier */
    returnValue =
        mpiMotorAmpEnableSet(motor,
                            FALSE);

    /* Disable capture */
    returnValue =
        mpiCaptureArm(capture,
                      FALSE);
    msgCHECK(returnValue);


    msgCHECK(returnValue);

    /* Configure axis  */
    returnValue =
        mpiAxisConfigGet(axis,
                         &axisConfig,
                         NULL);
    msgCHECK(returnValue);

    /* Set inPositionLimit  */
    axisConfig.inPosition.tolerance.positionFine = inPositionLimit;

    returnValue =
        mpiAxisConfigSet(axis,
                        &axisConfig,
                        NULL);
    msgCHECK(returnValue);



    /* Configure Motor */
    returnValue =
        mpiMotorConfigGet(motor,
                         &motorConfig,
                         &motorConfigXmp);
    msgCHECK(returnValue);

    /* Disable limit error, home, amp fault & H/W Limits, set encoder phase */

    /* Disable limit error */
    motorConfig.event[MPIEventTypeLIMIT_ERROR].action           = MPIActionNONE;
    motorConfig.event[MPIEventTypeLIMIT_ERROR].trigger.error    = (float)50000;

    /* Disable home event */
    motorConfig.event[MPIEventTypeHOME].action  = MPIActionNONE;

    /* Disable amp fault event */
    motorConfig.event[MPIEventTypeAMP_FAULT].action = MPIActionNONE;

    /* Disable neg. HW limit event */
    motorConfig.event[MPIEventTypeLIMIT_HW_NEG].action  = MPIActionNONE;

    /* Disable pos. HW limit event */
    motorConfig.event[MPIEventTypeLIMIT_HW_POS].action  = MPIActionNONE;

    /* Verify that transceivers are configured for input (default) */
    motorConfigXmp.Transceiver[TRANSC_A_ID].Config = IO_CONFIG_IN;
    motorConfigXmp.Transceiver[TRANSC_B_ID].Config = IO_CONFIG_IN;
    motorConfigXmp.Transceiver[TRANSC_C_ID].Config = IO_CONFIG_IN;


    /* Set encoder phase; 0 - for normal; 1 - for reversed */

#ifdef ReverseEncPhasing
    motorConfig.encoderPhase = 1;
#else
    motorConfig.encoderPhase = 0;
#endif

    /* Setup Motor commutation in open-loop mode  */
    commutation = &motorConfigXmp.Commutation;

    commutation->Mode        = MEIXmpCommModeOPEN_LOOP;
    commutation->Length      = nEncCountPerCycle;
    commutation->Scale       = (float)MEIXmpCOMM_TABLE_SIZE * N_CYCLES /
                               (float)commutation->Length;
    commutation->PhaseDelta  = MEIXmpCOMM_120DEGREES;
    commutation->OutputLevel = OpenDAC_Level;   /* Open-loop DAC level */
    commutation->Offset      = (long)0;

#if defined(ReverseDACPhasing)
    motorConfigXmp.Dac.Phase = MEIXmpDACPhaseINVERTED;
#else
    motorConfigXmp.Dac.Phase = MEIXmpDACPhaseNORMAL;
#endif

    /* Set configuration */
    returnValue =
        mpiMotorConfigSet(motor,
                        &motorConfig,
                        &motorConfigXmp);
    msgCHECK(returnValue);

    /* Get current Filter configuration */
    returnValue =
        mpiFilterGainGet(filter,
                        MEIFilterGainIndexDEFAULT,
                        &gain);
    msgCHECK(returnValue);

    pid = (MEIFilterGainPID *)&gain;

    /* Filter Controller control parameters */
    pid->gain.proportional          = (float)100.0; /* Kp must be set for your system */
    pid->gain.integral              = (float)0.0;   /* Ki set to zero for initial use */
    pid->gain.derivative            = (float)400.0; /* Kd must be set for your system */
    pid->feedForward.velocity       = (float)0.0;
    pid->feedForward.acceleration   = (float)0.0;
    pid->feedForward.friction       = (float)0.0;
    pid->integrationMax.moving      = (float)0.0;
    pid->integrationMax.rest        = (float)0.0;
    pid->output.limit               = (float)32767.0; /* closed-loop output limit */
    pid->output.offset              = (float)0.0;

    /* Set filter configuration  */
    returnValue =
        mpiFilterGainSet(filter,
                        MEIFilterGainIndexDEFAULT,
                        &gain);
    msgCHECK(returnValue);

    /*
       Create a Motion Object and append an Axis
       Note 1 - separate axis appends will be required for coordinated motion
       Note 2 - Axis Map does not take effect until motion is commanded!
     */
    motion =
         mpiMotionCreate(control,
                         motionNumber,
                         axis);
    msgCHECK(mpiMotionValidate(motion));


    /* Clear out any previous errors */
    returnValue =
        mpiMotionAction(motion,
                        MPIActionRESET);
    msgCHECK(returnValue);


    /* Immediately send Map to controller */
    returnValue =
        mpiMotionAction(motion,
                        (MPIAction)MEIActionMAP);
    msgCHECK(returnValue);


    /* Display commutation parameters */
    returnValue =
        mpiMotorConfigGet(motor,
                          NULL,
                          &motorConfigXmp);
    msgCHECK(returnValue);


 #ifdef DumpCommParameters


    printf("Motor %ld:\n",
            motorNumber);

    printf("\tCommutation Length before O-L move = %ld\n",
            motorConfigXmp.Commutation.Length);

    printf("\tCommutation Scale = %f\n",
            motorConfigXmp.Commutation.Scale);

    printf("\tCommutation Theta = %ld\n",
            motorConfigXmp.Commutation.Theta);

#endif

    if (motorConfigXmp.Commutation.Length != 0) {

        double  phaseAngle;
        long tableIndex;

        tableIndex =
            ((long)(motorConfigXmp.Commutation.Theta *
              motorConfigXmp.Commutation.Scale)) &
             (MEIXmpCOMM_TABLE_SIZE - 1);

        phaseAngle =
             (double)tableIndex * 360.0/
             (double)MEIXmpCOMM_TABLE_SIZE;

        LminusTh = (double)(motorConfigXmp.Commutation.Length -
              motorConfigXmp.Commutation.Theta);

        printf("\tPhase angle = %lf degrees\n",
                phaseAngle);
    }

    /* Set configuration */
    returnValue =
        mpiMotorConfigSet(motor,
                        &motorConfig,
                        &motorConfigXmp);
    msgCHECK(returnValue);


    /*
       Implement an open-loop "move" (without drive enabled)to
       allow Trajectory Calculator Delta to move commutation
       Theta to the beginning of the commutation table (w/o motion).
       Therefore, if Theta != 0:

                Move distance = Length - Theta (counts)
     */

    if((long)(motorConfigXmp.Commutation.Theta *
              motorConfigXmp.Commutation.Scale) != 0)
        {

        returnValue =
            mpiAxisCommandPositionGet(axis,
                                  &command);
        msgCHECK(returnValue);

        trajectory.velocity     = FAST;
        trajectory.acceleration = FAST_ACCEL;
        trajectory.deceleration = FAST_ACCEL;

        params.trapezoidal.trajectory = &trajectory;
        endposition =
        command + LminusTh;
        params.trapezoidal.position = &endposition;

        meiPlatformSleep(25);

        /*   Start "virtual" motion  */
        returnValue =
            mpiMotionStart(motion,
                           MPIMotionTypeTRAPEZOIDAL,
                         &params);
        msgCHECK(returnValue);

        /*   Delay to allow "virtual" motion to complete  */
        meiPlatformSleep(500);

        }

    /* Zero command and actual positions */
        SetPositionZero(axis);



    /* Read and display the transceiver IO bit */

    returnValue =
        mpiMotorIoGet(motor,
                      &io);
    msgCHECK(returnValue);


/*
   At this point we are still in open-loop mode with the drive disabled.
   The combined transceiver word provides the basic logic needed to establish
   the commutation Offset (Offset range: 0 to 1023) required for the active
   Hall region.
 */

    iTranState = ((io.input & TRANSC_A_MASK) + (io.input & TRANSC_B_MASK) +
                  (io.input & TRANSC_C_MASK));

    printf("\n%s: %d\n","Trans A Input bit",(io.input & TRANSC_A_MASK));
    printf("\n%s: %d\n","Trans B Input bit",(io.input & TRANSC_B_MASK));
    printf("\n%s: %d\n","Trans C Input bit",(io.input & TRANSC_C_MASK));
    printf("\n%s: %d\n","Trans Input Word",iTranState);


/* Configure capture for Transceiver input trigger */
    returnValue =
        mpiCaptureConfigGet(capture,
                            &captureConfig,
                            NULL);
    msgCHECK(returnValue);

/* Set commutation Offset and expected Hall transition */

    switch (iTranState)
    {

        case 1: /* w/CW rotation: next Hall Region 3, next Hall/Trans. edge B+ */
            {
            iOffset     = 256;
            captureConfig.trigger.mask = MEIMotorTransceiverMaskB;
            captureConfig.trigger.pattern = MEIMotorTransceiverMaskB;
            break;
            }

        case 2: /* w/CW rotation: next Hall Region 6, next Hall/Trans. edge C+ */
            {
            iOffset     =  597;
            captureConfig.trigger.mask = MEIMotorTransceiverMaskC;
            captureConfig.trigger.pattern = MEIMotorTransceiverMaskC;
            break;
            }

        case 3: /* w/CW rotation: next Hall Region 2, next Hall/Trans. edge A- */
            {
            iOffset     =  426;
            captureConfig.trigger.mask = MEIMotorTransceiverMaskA;
            captureConfig.trigger.pattern = 0;
            break;
            }

        case 4: /* w/CW rotation: next Hall Region 5, next Hall/Trans. edge A+ */
            {
            iOffset     =  938;
            captureConfig.trigger.mask = MEIMotorTransceiverMaskA;
            captureConfig.trigger.pattern = MEIMotorTransceiverMaskA;
            break;
            }

        case 5: /* w/CW rotation: next Hall Region 1, next Hall/Trans. edge C- */
            {
            iOffset     =   85;
            captureConfig.trigger.mask = MEIMotorTransceiverMaskC;
            captureConfig.trigger.pattern = 0;
            break;
            }

        case 6: /* w/CW rotation: next Hall Region 4, next Hall/Trans. edge B- */
            {
            iOffset     =  768;
            captureConfig.trigger.mask = MEIMotorTransceiverMaskB;
            captureConfig.trigger.pattern = 0;
            break;
            }

        default:
            {
                printf("\n Incorrect read of Transceivers \n");
                exit(0);
            }
    }


    returnValue =
        mpiCaptureConfigSet(capture,
                            &captureConfig,
                            NULL);
    msgCHECK(returnValue);


    /* Configure Home Event action */
    returnValue =
        mpiMotorEventConfigGet(motor,
                               MPIEventTypeHOME,
                               &eventConfig,
                               NULL);
    msgCHECK(returnValue);

    eventConfig.action = MPIActionNONE;     /* no event */
    eventConfig.trigger.polarity = TRUE;

    returnValue =
        mpiMotorEventConfigSet(motor,
                               MPIEventTypeHOME,
                               &eventConfig,
                               NULL);
    msgCHECK(returnValue);

    /* Arm the capture */
    returnValue =
        mpiCaptureArm(capture,
                      TRUE);
    msgCHECK(returnValue);


    /* Get motor configuration again */
    returnValue =
        mpiMotorConfigGet(motor,
                        &motorConfig,
                        &motorConfigXmp);
    msgCHECK(returnValue);


    /* Setup commutation with closed-loop control and new Offset */

    commutation->Mode        = MEIXmpCommModeCLOSED_LOOP;
    commutation->Offset      = iOffset;     /* Hall updated Offset */

    /* Set configuration */
    returnValue =
        mpiMotorConfigSet(motor,
                        &motorConfig,
                        &motorConfigXmp);
    msgCHECK(returnValue);

    /* Read original position for capture (origin) */

    returnValue =
        mpiAxisOriginGet(axis,
                         &origin);
    meiASSERT(returnValue == MPIMessageOK);

    origLatchPosition = origin;

    returnValue =
        mpiAxisOriginSet(axis,
                         origin);
    meiASSERT(returnValue == MPIMessageOK);


#ifdef DumpCommParameters

    /* Display commutation parameters again*/
    returnValue =
        mpiMotorConfigGet(motor,
                          NULL,
                          &motorConfigXmp);
    msgCHECK(returnValue);


    printf("\tCommutation Length C-L = %ld\n",
            motorConfigXmp.Commutation.Length);


    printf("\tCommutation Theta = %ld\n",
            motorConfigXmp.Commutation.Theta);

    if (motorConfigXmp.Commutation.Length != 0) {

        double  phaseAngle;
        long tableIndex;

        tableIndex =
            ((long)(motorConfigXmp.Commutation.Theta *
              motorConfigXmp.Commutation.Scale)) &
             (MEIXmpCOMM_TABLE_SIZE - 1);

        phaseAngle =
             (double)tableIndex * 360.0/
             (double)MEIXmpCOMM_TABLE_SIZE;

        printf("\tPhase angle = %lf degrees\n",
                phaseAngle);
    }

    /* Set configuration */
    returnValue =
        mpiMotorConfigSet(motor,
                        &motorConfig,
                        &motorConfigXmp);
    msgCHECK(returnValue);

#endif


    /* Enable the amplifier */
    returnValue =
        mpiMotorAmpEnableSet(motor,
                            TRUE);
    msgCHECK(returnValue);

    /*
       Stage/motor will servo on position with initial (Hall)
       estimate of commutation position.
       Wait period: 0.5 seconds in this example.
     */

    meiPlatformSleep(500);


    /*
        Implement a closed-loop move to the first Hall transition.
        Upon reaching transition point, latch position and update
        commutation table entry point.

        The move is currently set for +72 elec. degrees. Since the
        commutation max. error is +/- 30 deg based on a 60 deg sector,
        this allows up to 12 electrical degrees of physical mis-alignment
        of the hall sensor.
     */

    returnValue =
        mpiAxisCommandPositionGet(axis,
                                  &command);
    msgCHECK(returnValue);

    trajectory.velocity     = SLOW;
    trajectory.acceleration = SLOW_ACCEL;
    trajectory.deceleration = SLOW_ACCEL;

    params.trapezoidal.trajectory = &trajectory;
    endposition =
        command +
        ((double)(nEncCountPerCycle) / ((double)(N_CYCLES * 5.0)));
    params.trapezoidal.position = &endposition;

    meiPlatformSleep(25);

    /* Start motion */
    returnValue =
        mpiMotionStart(motion,
                       MPIMotionTypeTRAPEZOIDAL,
                       &params);
    msgCHECK(returnValue);

    printf("\n Moving...(hit any key after motion completes)...\n\n");

    /* State Machine - Poll capture status, update display, etc. */
    while (meiPlatformKey(MPIWaitPOLL) <= 0) {
        returnValue =
            mpiCaptureStatus(capture,
                             &captureStatus,
                             NULL);
        msgCHECK(returnValue);


        if (captureStatus.state == MPICaptureStateCAPTURED) {

            latchedPosition = captureStatus.latch[0];

            /* Re-arm position capture */
            returnValue =
                mpiCaptureArm(capture,
                              TRUE);
            msgCHECK(returnValue);
        }
    }

    latchPosChange = latchedPosition - origLatchPosition;

    printf("\n iOffset(orig.) = %d", iOffset);
    iOffset += (long)((((float)commutation->Length)/(N_CYCLES*12) - latchPosChange)*(commutation->Scale));
    printf("\n iOffset(final) = %d\n\n", iOffset);

    /* Get motor configuration again */
    returnValue =
        mpiMotorConfigGet(motor,
                        &motorConfig,
                        &motorConfigXmp);
    msgCHECK(returnValue);


    /* Update commutation Offset based on Hall transition location */

    commutation->Offset      = iOffset;     /* Hall updated Offset */

    /* Set configuration */
    returnValue =
        mpiMotorConfigSet(motor,
                        &motorConfig,
                        &motorConfigXmp);
    msgCHECK(returnValue);

    /*
        Delete Objects
     */
    returnValue = mpiMotionDelete(motion);
    msgCHECK(returnValue);

    returnValue = mpiCaptureDelete(capture);
    msgCHECK(returnValue);

    returnValue = mpiMotorDelete(motor);
    msgCHECK(returnValue);

    returnValue = mpiFilterDelete(filter);
    msgCHECK(returnValue);

    returnValue = mpiAxisDelete(axis);
    msgCHECK(returnValue);

    returnValue = mpiControlDelete(control);
    msgCHECK(returnValue);

    return ((int)returnValue);
}


void SetPositionZero(MPIAxis axis)
{
    double  actualPosition;
    double  origin;

    long    returnValue;

    returnValue =
        mpiAxisActualPositionGet(axis,
                                 &actualPosition);
    meiASSERT(returnValue == MPIMessageOK);

    returnValue =
        mpiAxisOriginGet(axis,
                         &origin);
    meiASSERT(returnValue == MPIMessageOK);

    actualPosition += origin;

    returnValue =
        mpiAxisOriginSet(axis,
                         actualPosition);
    meiASSERT(returnValue == MPIMessageOK);

    meiPlatformSleep(15);

    actualPosition = 0;

    returnValue =
        mpiAxisCommandPositionSet(axis,
                                  actualPosition);
    meiASSERT(returnValue == MPIMessageOK);

    meiPlatformSleep(15);
};